mirror of https://github.com/ArduPilot/ardupilot
Rover: use DataFlash should_log to determine raw IMU logging
This commit is contained in:
parent
949e07c7e3
commit
dcad79bdef
|
@ -350,8 +350,6 @@ void Rover::one_second_loop(void)
|
|||
counter = 0;
|
||||
}
|
||||
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
|
||||
// update home position if not soft armed and gps position has
|
||||
// changed. Update every 1s at most
|
||||
if (!hal.util->get_soft_armed() &&
|
||||
|
|
|
@ -165,6 +165,8 @@ void Rover::init_ardupilot()
|
|||
|
||||
rc_override_active = hal.rcin->set_overrides(rc_override, 8);
|
||||
|
||||
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
||||
|
||||
set_control_channels();
|
||||
init_rc_in(); // sets up rc channels from radio
|
||||
init_rc_out(); // sets up the timer libs
|
||||
|
@ -259,9 +261,6 @@ void Rover::startup_ground(void)
|
|||
// so set serial ports non-blocking once we are ready to drive
|
||||
serial_manager.set_blocking_writes_all(false);
|
||||
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
ins.set_dataflash(&DataFlash);
|
||||
|
||||
gcs_send_text(MAV_SEVERITY_INFO, "Ready to drive");
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue