Copter: use DataFlash should_log to determine raw logging

This commit is contained in:
Peter Barker 2017-06-27 14:42:20 +10:00 committed by Francisco Ferreira
parent 6ae86a0b8c
commit 776d691c79
2 changed files with 1 additions and 5 deletions

View File

@ -494,9 +494,6 @@ void Copter::one_hz_loop()
check_usb_mux();
// enable/disable raw gyro/accel logging
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
// log terrain data
terrain_logging();

View File

@ -314,8 +314,7 @@ void Copter::init_ardupilot()
// enable CPU failsafe
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);
// enable output to motors
arming.pre_arm_rc_checks(true);