From dcad79bdef371c10cd591ba700eb33376e9a9541 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 27 Jun 2017 15:26:14 +1000 Subject: [PATCH] Rover: use DataFlash should_log to determine raw IMU logging --- APMrover2/APMrover2.cpp | 2 -- APMrover2/system.cpp | 5 ++--- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 6567156d23..97acf8f10a 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -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() && diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 3e5082dea1..34ba45603d 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -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"); }