mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: use primary accel for accel_ef
Logs from Randy show that the copter INav code can't handle the accelerometer sensor changing.
This commit is contained in:
parent
2c85a7ba56
commit
9a5ecc9541
|
@ -128,7 +128,7 @@ public:
|
|||
}
|
||||
|
||||
// accelerometer values in the earth frame in m/s/s
|
||||
const Vector3f &get_accel_ef(void) const { return _accel_ef[_active_accel_instance]; }
|
||||
const Vector3f &get_accel_ef(void) const { return _accel_ef[_ins.get_primary_accel()]; }
|
||||
|
||||
// Methods
|
||||
virtual void update(void) = 0;
|
||||
|
|
Loading…
Reference in New Issue