Sub: use DataFlash should_log to determine raw IMU logging

This commit is contained in:
Peter Barker 2017-06-27 16:36:18 +10:00 committed by Francisco Ferreira
parent dcad79bdef
commit 7cd794201e
2 changed files with 1 additions and 5 deletions

View File

@ -378,9 +378,6 @@ void Sub::one_hz_loop()
// update position controller alt limits
update_poscon_alt_max();
// enable/disable raw gyro/accel logging
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
// log terrain data
terrain_logging();
}

View File

@ -179,8 +179,7 @@ void Sub::init_ardupilot()
// enable CPU failsafe
mainloop_failsafe_enable();
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash);
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
// init vehicle capabilties
init_capabilities();