-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Added mrs_uav_system configs for robofly and a300
- Loading branch information
1 parent
7505fff
commit 4d923d7
Showing
2 changed files
with
163 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,82 @@ | ||
uav_mass: 1.21 # overall mass of the drone | ||
|
||
# force to throttle sqrt(force / motor_params.n_motors) * motor_params.A + motor_params.B; | ||
# for single rotor max 19,23432N it is sqrt(19,23432) * 0.2600 - 0.1765 | ||
|
||
#those motor params are for 20,475625N max thrust 1 throttle ... ((1+0.1765)/0.26)^2 | ||
#for zero throttle we get force of single rotor = (0.1765/0.26)^2 = 0,460832101N | ||
# zero throttle thrist must correspond to min_rpm sqrt(0.460832101/0.000000045) = 3200,111459864 | ||
motor_params: | ||
n_motors: 4 | ||
a: 0.2600 | ||
b: -0.1765 | ||
|
||
# these model parameters can be used when | ||
# - 'attitude rate', and/or | ||
# - 'actuator control' | ||
# are done by the MRS system. | ||
model_params: | ||
arm_length: 0.15 # [m] | ||
body_height: 0.05 # [m] | ||
|
||
propulsion: | ||
# force [N] = force_constant * rpm^2 | ||
# for 21400 max rpm it is 20,475625 N then the force constant is 0.000000045 | ||
force_constant: 0.000000045 | ||
|
||
# torque [Nm] = torque_constant * force [N] | ||
torque_constant: 0.012 # 0.014 torque computed from power (efficiency estimated as 85% ) | ||
|
||
prop_radius: 0.089 # [m] | ||
|
||
# allocation motors -> torques | ||
|
||
# quadrotor X configuration | ||
# hexarotor X configuration | ||
# [roll torque, [ [RPM_1^2, | ||
# pitch torque, = Alloc * RPM_2^2, | ||
# yaw torque, Matrix ... | ||
# thrust force] ] RPM_n_motors^2] | ||
allocation_matrix: [ | ||
-0.707, 0.707, 0.707, -0.707, # *= force_constant*arm_length | ||
-0.707, 0.707, -0.707, 0.707, # *= force_constant*arm_length | ||
-1 , -1 , 1 , 1 , # *= torque_constant*force_constant | ||
1 , 1 , 1 , 1 , # *= force_constant | ||
] | ||
|
||
# The UAV's inertia is approximated as a cilinder using the parameters above | ||
# Alternatively, you can provide inertia matrix directly using the following parameter: | ||
# inertia_matrix: [] | ||
|
||
rpm: | ||
min: 3200 # [revolutions/minute] | ||
max: 21400 # [revolutions/minute] | ||
|
||
mrs_uav_managers: | ||
constraint_manager: | ||
default_constraints: | ||
gps_garmin: "medium" | ||
gps_baro: "medium" | ||
rtk: "medium" | ||
aloam: "slow" | ||
hector_garmin: "slow" | ||
vio: "slow" | ||
optflow: "slow" | ||
other: "slow" | ||
ground_truth: "medium" | ||
|
||
safety: | ||
tilt_limit: | ||
eland: | ||
enabled: false | ||
|
||
disarm: | ||
enabled: false | ||
|
||
tilt_error_disarm: | ||
enabled: false | ||
timeout: 0.5 # [s] # for how long the error has to be present to disarm | ||
error_threshold: deg(20) # [rad] | ||
|
||
yaw_error_eland: | ||
enabled: false |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,81 @@ | ||
uav_mass: 0.8 # overall mass of the drone | ||
|
||
# force to throttle sqrt(force / motor_params.n_motors) * motor_params.A + motor_params.B; | ||
# for single rotor max 19,23432N it is sqrt(19,23432) * 0.2600 - 0.1765 | ||
|
||
#those motor params are for 20,475625N max thrust 1 throttle ... ((1+0.1765)/0.26)^2 | ||
#for zero throttle we get force of single rotor = (0.1765/0.26)^2 = 0,460832101N | ||
# zero throttle thrist must correspond to min_rpm sqrt(0.460832101/0.000000045) = 3200,111459864 | ||
motor_params: | ||
n_motors: 4 | ||
a: 0.2882 | ||
b: -0.0895 | ||
# these model parameters can be used when | ||
# - 'attitude rate', and/or | ||
# - 'actuator control' | ||
# are done by the MRS system. | ||
model_params: | ||
arm_length: 0.135 # [m] | ||
body_height: 0.05 # [m] | ||
|
||
propulsion: | ||
# force [N] = force_constant * rpm^2 | ||
# for 21400 max rpm it is 20,475625 N then the force constant is 0.000000045 | ||
force_constant: 0.000000045 | ||
|
||
# torque [Nm] = torque_constant * force [N] | ||
torque_constant: 0.012 # 0.014 torque computed from power (efficiency estimated as 85% ) | ||
|
||
prop_radius: 0.065 # [m] | ||
|
||
# allocation motors -> torques | ||
|
||
# quadrotor X configuration | ||
# hexarotor X configuration | ||
# [roll torque, [ [RPM_1^2, | ||
# pitch torque, = Alloc * RPM_2^2, | ||
# yaw torque, Matrix ... | ||
# thrust force] ] RPM_n_motors^2] | ||
allocation_matrix: [ | ||
-0.707, 0.707, 0.707, -0.707, # *= force_constant*arm_length | ||
-0.707, 0.707, -0.707, 0.707, # *= force_constant*arm_length | ||
-1 , -1 , 1 , 1 , # *= torque_constant*force_constant | ||
1 , 1 , 1 , 1 , # *= force_constant | ||
] | ||
|
||
# The UAV's inertia is approximated as a cilinder using the parameters above | ||
# Alternatively, you can provide inertia matrix directly using the following parameter: | ||
# inertia_matrix: [] | ||
|
||
rpm: | ||
min: 2400 # [revolutions/minute] | ||
max: 3200 # [revolutions/minute] | ||
|
||
mrs_uav_managers: | ||
constraint_manager: | ||
default_constraints: | ||
gps_garmin: "medium" | ||
gps_baro: "medium" | ||
rtk: "medium" | ||
aloam: "slow" | ||
hector_garmin: "slow" | ||
vio: "slow" | ||
optflow: "slow" | ||
other: "slow" | ||
ground_truth: "medium" | ||
|
||
safety: | ||
tilt_limit: | ||
eland: | ||
enabled: false | ||
|
||
disarm: | ||
enabled: false | ||
|
||
tilt_error_disarm: | ||
enabled: false | ||
timeout: 0.5 # [s] # for how long the error has to be present to disarm | ||
error_threshold: deg(20) # [rad] | ||
|
||
yaw_error_eland: | ||
enabled: false |