mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
Copter: use DataFlash should_log to determine raw logging
This commit is contained in:
parent
6ae86a0b8c
commit
776d691c79
@ -494,9 +494,6 @@ void Copter::one_hz_loop()
|
|||||||
|
|
||||||
check_usb_mux();
|
check_usb_mux();
|
||||||
|
|
||||||
// enable/disable raw gyro/accel logging
|
|
||||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
|
||||||
|
|
||||||
// log terrain data
|
// log terrain data
|
||||||
terrain_logging();
|
terrain_logging();
|
||||||
|
|
||||||
|
@ -314,8 +314,7 @@ void Copter::init_ardupilot()
|
|||||||
// enable CPU failsafe
|
// enable CPU failsafe
|
||||||
failsafe_enable();
|
failsafe_enable();
|
||||||
|
|
||||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
||||||
ins.set_dataflash(&DataFlash);
|
|
||||||
|
|
||||||
// enable output to motors
|
// enable output to motors
|
||||||
arming.pre_arm_rc_checks(true);
|
arming.pre_arm_rc_checks(true);
|
||||||
|
Loading…
Reference in New Issue
Block a user