-
Notifications
You must be signed in to change notification settings - Fork 8
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
move hany drone params to configs/dynamics
- Loading branch information
1 parent
8cc4d3a
commit 70370ec
Showing
3 changed files
with
36 additions
and
2 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,5 @@ | ||
# Hany Quadcopter | ||
|
||
| | | | ||
|-|-| | ||
| <img src="https://docs.raccoonlab.co/assets/img/airframe.686280a7.png" alt="drawing" width="466"/> | <img src="https://docs.raccoonlab.co/assets/img/view.8746517f.png" alt="drawing" width="333"/> | |
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,29 @@ | ||
# Small Quadcopter Configuration | ||
# This configuration defines the dynamics properties for a small quadcopter | ||
# based on the RaccoonLab Cyphal/DroneCAN Quadcopter KIT. It is designed for | ||
# use with the PX4 autopilot system. | ||
|
||
vehicle_mass : 1.5 # kg | ||
motor_time_constant: 0.02 # sec | ||
motor_rotational_inertia: 6.62e-6 # kg m^2 | ||
thrust_coefficient: 1.91e-6 # N/(rad/s)^2" | ||
torque_coefficient: 2.6e-7 # Nm/(rad/s)^2 | ||
drag_coefficient: 0.1 # N/(m/s) | ||
aeromoment_coefficient_xx: 0.003 # Nm/(rad/s)^2 | ||
aeromoment_coefficient_yy: 0.003 # Nm/(rad/s)^2 | ||
aeromoment_coefficient_zz: 0.003 # Nm/(rad/s)^2 | ||
vehicle_inertia_xx: 0.0100 # | ||
vehicle_inertia_yy: 0.0100 # | ||
vehicle_inertia_zz: 0.0150 # | ||
max_prop_speed: 2200 # rad/s | ||
moment_process_noise: 1.25e-7 # (Nm)^2 s | ||
force_process_noise: 0.0005 # N^2 s" | ||
|
||
moment_arm: 0.08 # m | ||
|
||
accelerometer_biasprocess: 0.0 # m^2/s^5, 1.0e-7 | ||
gyroscope_biasprocess: 0.0 # rad^2/s^3, 1.0e-7 | ||
accelerometer_biasinitvar: 0.00001 # (m/s^2)^2, 0.005 | ||
gyroscope_biasinitvar: 0.00001 # (rad/s)^2, 0.003 | ||
accelerometer_variance: 0.0001 # m^2/s^4, 0.001 | ||
gyroscope_variance: 0.00001 # rad^2/s^2, 0.001 |
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