Browse Source

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
master
Andrew Tridgell 9 years ago
parent
commit
54d1cc7e50
  1. 4
      ArduCopter/motors.cpp

4
ArduCopter/motors.cpp

@ -221,8 +221,8 @@ void Copter::init_disarm_motors() @@ -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…
Cancel
Save