mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: move responsibility for logging into library
This commit is contained in:
parent
14a8bf3aec
commit
aae9dc55e3
@ -171,10 +171,6 @@ void Sub::update_batt_compass()
|
|||||||
// update compass with throttle value - used for compassmot
|
// update compass with throttle value - used for compassmot
|
||||||
compass.set_throttle(motors.get_throttle());
|
compass.set_throttle(motors.get_throttle());
|
||||||
compass.read();
|
compass.read();
|
||||||
// log compass information
|
|
||||||
if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) {
|
|
||||||
logger.Write_Compass();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -104,6 +104,7 @@ void Sub::init_ardupilot()
|
|||||||
gps.set_log_gps_bit(MASK_LOG_GPS);
|
gps.set_log_gps_bit(MASK_LOG_GPS);
|
||||||
gps.init(serial_manager);
|
gps.init(serial_manager);
|
||||||
|
|
||||||
|
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
||||||
AP::compass().init();
|
AP::compass().init();
|
||||||
|
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user