Copter: only save offsets for Compass::LEARN_EKF
this means by default that one flight one affect the next one, which makes it more robust in case of a bad flight
This commit is contained in:
parent
ed999a283f
commit
54d1cc7e50
@ -221,8 +221,8 @@ void Copter::init_disarm_motors()
|
||||
gcs_send_text(MAV_SEVERITY_INFO, "Disarming motors");
|
||||
#endif
|
||||
|
||||
// save compass offsets learned by the EKF
|
||||
if (ahrs.use_compass()) {
|
||||
// save compass offsets learned by the EKF if enabled
|
||||
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
|
||||
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
||||
Vector3f magOffsets;
|
||||
if (ahrs.getMagOffsets(i, magOffsets)) {
|
||||
|
Loading…
Reference in New Issue
Block a user