From 74e0d6c60ae2e28b28f8bfdf9e28fe7bfd36cd1d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 1 May 2017 16:12:05 +1000 Subject: [PATCH] Rover: move init of DataFlash references into vehicle init It is possible to start a log before the existing codepath is crossed. --- APMrover2/Log.cpp | 4 ---- APMrover2/system.cpp | 6 ++++++ 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 6d5439b07f..00b312051a 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -517,10 +517,6 @@ void Rover::Log_Write_Vehicle_Startup_Messages() void Rover::start_logging() { in_mavlink_delay = true; - DataFlash.set_mission(&mission); - DataFlash.setVehicle_Startup_Log_Writer( - FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) - ); DataFlash.StartNewLog(); in_mavlink_delay = false; } diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index f3d5251ab9..e36ab20db6 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -249,6 +249,12 @@ void Rover::startup_ground(void) // initialise mission library mission.init(); + // initialise DataFlash library + DataFlash.set_mission(&mission); + DataFlash.setVehicle_Startup_Log_Writer( + FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) + ); + // we don't want writes to the serial port to cause us to pause // so set serial ports non-blocking once we are ready to drive serial_manager.set_blocking_writes_all(false);