Browse Source

Plane: use DataFlash should_log to determine raw IMU logging

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
949e07c7e3
  1. 2
      ArduPlane/ArduPlane.cpp
  2. 5
      ArduPlane/system.cpp

2
ArduPlane/ArduPlane.cpp

@ -356,8 +356,6 @@ void Plane::one_second_loop() @@ -356,8 +356,6 @@ void Plane::one_second_loop()
}
#endif
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
// update home position if soft armed and gps position has
// changed. Update every 5s at most
if (!hal.util->get_soft_armed() &&

5
ArduPlane/system.cpp

@ -100,6 +100,8 @@ void Plane::init_ardupilot() @@ -100,6 +100,8 @@ void Plane::init_ardupilot()
}
#endif
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
set_control_channels();
#if HAVE_PX4_MIXER
@ -312,9 +314,6 @@ void Plane::startup_ground(void) @@ -312,9 +314,6 @@ void Plane::startup_ground(void)
// ready to fly
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,"Ground start complete");
}

Loading…
Cancel
Save