mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_AHRS: added get_yaw_rate_earth()
used to estimate course correction on takeoff
This commit is contained in:
parent
41ce8c2abd
commit
809b6cc855
@ -160,6 +160,9 @@ public:
|
||||
// accelerometer values in the earth frame in m/s/s
|
||||
const Vector3f &get_accel_ef(void) const { return _accel_ef[_ins.get_primary_accel()]; }
|
||||
|
||||
// get yaw rate in earth frame in radians/sec
|
||||
float get_yaw_rate_earth(void) const { return get_gyro() * get_dcm_matrix().c; }
|
||||
|
||||
// Methods
|
||||
virtual void update(void) = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user