-
Notifications
You must be signed in to change notification settings - Fork 13.7k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add gyroscopic torque cancellation loop for single-rotor drones #21489
base: main
Are you sure you want to change the base?
Conversation
@@ -109,6 +115,7 @@ class RateControl | |||
matrix::Vector3f _gain_d; ///< rate control derivative gain | |||
matrix::Vector3f _lim_int; ///< integrator term maximum absolute value | |||
matrix::Vector3f _gain_ff; ///< direct rate to torque feed forward gain only useful for helicopters | |||
float _rotor_angular_momentum; ///< used to cancel out the gyroscopic torque generated by the rotors |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
float _rotor_angular_momentum; ///< used to cancel out the gyroscopic torque generated by the rotors | |
float _rotor_angular_momentum{}; ///< used to cancel out the gyroscopic torque generated by the rotors |
1a8dcbb
to
ffed768
Compare
const bool esc_connected = (esc_status.esc_online_flags & (1 << esc)) || (esc_report.esc_rpm != 0); | ||
|
||
// assuming all the rotors are in the same plane, the gyroscopic torque is proportional to the | ||
// difference between the CW and CCW rotation speed |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
FYI for some ESCs (like certain UAVCAN setups) the RPM is reported +/-, but in a lot of other cases (like dshot) it's always reported positive.
This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there: |
Single (rigid) rotor aircrafts have their dynamics dominated by the gyroscopic torque. Compensating for this effect by a feedback greatly improves stability. Multirotors can also benefit from this feature when the difference in RPM between the CW and CCW rotors is large (the sum of the angular momentum of the rotors is non zero).
🔎 FLASH Analysispx4_fmu-v5x [Total VM Diff: 2632 byte (0.13 %)]
px4_fmu-v6x [Total VM Diff: 2744 byte (0.13 %)]
Updated: 2025-01-28T14:34:08 |
Solved Problem
Single-(rigid)rotor drones have their dynamics dominated by the gyroscopic torque generated by a fast spinning disk. That torque creates a strong coupling between the roll-pitch axes that makes almost impossible to tune correctly.
Solution
Add a feedback loop in the rate controller that cancels-out the gyroscopic torque of the drone based on the rotor speed and the angular velocity of the drone ("anti-precession loop").
Changelog Entry
For release notes:
Test coverage
Flown on my single ducted-fan vehicle:
![IMG_20230213_085309](https://user-images.githubusercontent.com/14822839/232867533-45a9a2ab-ff8c-473b-8884-54dd754c553d.jpg)
https://youtu.be/u2cETOyuJ20