mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: remove compass learn of offsets
This saves 1k of flash and the interference on most copters makes this option unusable anyway.
This commit is contained in:
parent
d6890ce878
commit
7202aa00da
@ -1087,9 +1087,7 @@ static void update_batt_compass(void)
|
||||
if(g.compass_enabled) {
|
||||
// update compass with throttle value - used for compassmot
|
||||
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
|
||||
if (compass.read()) {
|
||||
compass.learn_offsets();
|
||||
}
|
||||
compass.read();
|
||||
// log compass information
|
||||
if (g.log_bitmask & MASK_LOG_COMPASS) {
|
||||
Log_Write_Compass();
|
||||
|
Loading…
Reference in New Issue
Block a user