mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AHRS: include the P terms in get_gyro()
this makes it more useful for navigation controllers
This commit is contained in:
parent
acc6adf6e9
commit
136c03c3c0
@ -28,7 +28,7 @@ public:
|
||||
}
|
||||
|
||||
// return the smoothed gyro vector corrected for drift
|
||||
Vector3f get_gyro(void) {return _omega; }
|
||||
Vector3f get_gyro(void) {return _omega + _omega_P + _omega_yaw_P; }
|
||||
Matrix3f get_dcm_matrix(void) {return _dcm_matrix; }
|
||||
|
||||
// return the current drift correction integrator value
|
||||
|
Loading…
Reference in New Issue
Block a user