-
-
Notifications
You must be signed in to change notification settings - Fork 29
/
Copy pathquad.yaml
146 lines (129 loc) · 6.94 KB
/
quad.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
use_rerun: true # Enable visualization using rerun.io
render_depth: true # Enable rendering depth
use_multithreading_depth_rendering: true # Enable multithreading for depth rendering for large resolution (above 32x24)
use_rk4_for_dynamics_update: false # Enable Runge-Kutta 4th order integration for dynamics, otherwise Euler integration is used
use_rk4_for_dynamics_control: false # Enable Runge-Kutta 4th order integration for dynamics, otherwise Euler integration is used
max_render_threads: 8 # Maximum number of threads for rendering
rerun_blueprint: "config/peng_default_blueprint.rbl"
simulation:
control_frequency: 200 # Frequency of control loop execution (Hz)
simulation_frequency: 1000 # Frequency of physics simulation updates (Hz)
log_frequency: 20 # Frequency of data logging (Hz)
duration: 90.0 # Total duration of the simulation (seconds)
quadrotor:
mass: 1.3 # Mass of the quadrotor (kg)
gravity: 9.81 # Gravitational acceleration (m/s^2)
drag_coefficient: 0.000 # Aerodynamic drag coefficient
# Inertia matrix [Ixx, Ixy, Ixz, Iyx, Iyy, Iyz, Izx, Izy, Izz] (kg*m^2)
inertia_matrix: [3.04e-3, 0.0, 0.0, 0.0, 4.55e-3, 0.0, 0.0, 0.0, 2.82e-3]
pid_controller:
pos_gains: # PID gains for position control
kp: [7.1, 7.1, 11.9] # Proportional gains [x, y, z]
kd: [2.4, 2.4, 6.7] # Derivative gains [x, y, z]
ki: [0.0, 0.0, 0.0] # Integral gains [x, y, z]
att_gains: # PID gains for attitude control
kp: [1.5, 1.5, 1.0] # Proportional gains [roll, pitch, yaw]
kd: [0.13, 0.13, 0.1] # Derivative gains [roll, pitch, yaw]
ki: [0.0, 0.0, 0.0] # Integral gains [roll, pitch, yaw]
pos_max_int: [10.0, 10.0, 10.0] # Maximum integral error for position control [x, y, z]
att_max_int: [0.5, 0.5, 0.5] # Maximum integral error for attitude control [roll, pitch, yaw]
imu:
accel_noise_std: 0.02 # Standard deviation of accelerometer noise (m/s^2)
gyro_noise_std: 0.01 # Standard deviation of gyroscope noise (rad/s)
accel_bias_std: 0.0001 # Standard deviation of accelerometer bias instability (m/s^2)
gyro_bias_std: 0.0001 # Standard deviation of gyroscope bias instability (rad/s)
maze:
lower_bounds: [-4.0, -2.0, 0.0] # Lower bounds of the maze [x, y, z] (m)
upper_bounds: [4.0, 2.0, 2.0] # Upper bounds of the maze [x, y, z] (m)
num_obstacles: 20 # Number of obstacles in the maze
obstacles_velocity_bounds: [0.2, 0.2, 0.1] # Maximum velocity of obstacles [x, y, z] (m/s)
obstacles_radius_bounds: [0.05, 0.1] # Range of obstacle radii [min, max] (m)
camera:
resolution: [128, 96] # Camera resolution [width, height] (pixels)
fov_vertical: 90 # Vertical Field of View (degrees)
near: 0.1 # Near clipping plane (m)
far: 5.0 # Far clipping plane (m)
rotation_transform: [0.0, 0.0, 1.0, -1.0, 0.0, 0.0, 0.0, -1.0, 0.0] # Rotates camera to positive x-axis
mesh:
division: 7 # Number of divisions in the mesh grid
spacing: 0.5 # Spacing between mesh lines (m)
planner_schedule:
# Minimum Jerk Line trajectory
- step: 1000 # Simulation step in ms to start this planner
planner_type: MinimumJerkLine
params:
end_position: [0.0, 0.0, 1.0] # Target end position [x, y, z] (m)
end_yaw: 0.0 # Target end yaw angle (rad)
duration: 2.5 # Duration of the trajectory (s)
# Lissajous trajectory
- step: 5000
planner_type: Lissajous
params:
center: [0.5, 0.5, 1.0] # Center of the Lissajous curve [x, y, z] (m)
amplitude: [0.5, 0.5, 0.2] # Amplitudes of the curve [x, y, z] (m)
frequency: [1.0, 2.0, 3.0] # Frequencies of the curve [x, y, z] (Hz)
phase: [0.0, 1.5707963267948966, 0.0] # Phase offsets [x, y, z] (rad)
duration: 20.0 # Duration of the trajectory (s)
end_yaw: 6.283185307179586 # Target end yaw angle (2*PI rad)
ramp_time: 5.0 # Time for smooth transition (s)
# Circular trajectory
- step: 27000
planner_type: Circle
params:
center: [0.5, 0.5, 1.0] # Center of the circle [x, y, z] (m)
radius: 0.5 # Radius of the circle (m)
angular_velocity: 1.0 # Angular velocity (rad/s)
duration: 5.0 # Duration of the trajectory (s)
ramp_time: 2.0 # Time for smooth transition (s)
# Another Minimum Jerk Line trajectory
- step: 32000
planner_type: MinimumJerkLine
params:
end_position: [-2.5, 0.0, 1.0] # Target end position [x, y, z] (m)
end_yaw: 0.0 # Target end yaw angle (rad)
duration: 3.0 # Duration of the trajectory (s)
# Obstacle Avoidance trajectory
- step: 35000
planner_type: ObstacleAvoidance
params:
target_position: [2.5, 1.0, 0.5] # Target position [x, y, z] (m)
duration: 10.0 # Duration of the trajectory (s)
end_yaw: 0.0 # Target end yaw angle (rad)
k_att: 0.03 # Attractive force gain
k_rep: 0.01 # Repulsive force gain
k_vortex: 0.005 # Vortex force gain
d0: 0.5 # Obstacle influence distance (m)
d_target: 0.5 # Target influence distance (m)
max_speed: 0.1 # Maximum speed (m/s)
# Minimum Snap Waypoint trajectory
- step: 45000
planner_type: MinimumSnapWaypoint
params:
waypoints: # List of waypoints [x, y, z] (m)
- [1.0, 1.0, 1.5]
- [-1.0, 1.0, 1.75]
- [0.0, -1.0, 1.0]
- [0.0, 0.0, 0.5]
yaws: [1.5707963267948966, 3.141592653589793, -1.5707963267948966, 0.0] # Yaw angles at waypoints (rad)
segment_times: [5.0, 5.0, 5.0, 5.0] # Time to reach each waypoint (s)
# Quadratic Polynomial trajectory
- step: 65000
planner_type: QPpolyTraj
params:
waypoints: # List of waypoints [x, y, z, yaw] in (m) and (rad) respectively
- [1.0, 1.0, 1.5, 1.5707963267948966]
- [-1.0, 1.0, 1.75, 3.141592653589793]
- [0.0, -1.0, 1.0, -1.5707963267948966]
- [0.0, 0.0, 0.5, 0.0]
segment_times: [5.0, 5.0, 5.0, 5.0] # Time to reach each waypoint (s)
polynomial_order: 9 # Order of the polynomial to be used in computing trajectory
minimize_derivative: 3 # Minimize which derivative in the QP problem (1->Velocity, 2->Acceleration, 3->Snap, 4->Jerk. Please note that derivative value greater than 4 is not supported)
smooth_upto: 4 # Ensure continuity upto which derivative. NOTE: This MUST be <= polynomial_order (1->Velocity, 2->Acceleration, 3->Snap, 4->Jerk. Please note that derivative value greater than 4 is not supported)
max_velocity: 4.0 # Maximum velocity constraint. Set to 0.0 to disregard these constraints. Please set reasonable values for this as it influences solver convergence or failure.
max_acceleration: 2.0 # Maximum acceleration constraint. Set to 0.0 to disregard these constraints. Please set reasonable values for this as it influences solver convergence or failure.
dt: 0.1 # Step time used while generating inequality constraints. Has no bearing if max_velocity or max_acceleration is set to 0.0. Please set reasonable value for this as it has a huge impact on OSQP solve time.
# Landing trajectory
- step: 85000
planner_type: Landing
params:
duration: 5.0 # Duration of the landing maneuver (s)