Browse Source

Rover: move init of DataFlash references into vehicle init

It is possible to start a log before the existing codepath is crossed.
mission-4.1.18
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
74e0d6c60a
  1. 4
      APMrover2/Log.cpp
  2. 6
      APMrover2/system.cpp

4
APMrover2/Log.cpp

@ -517,10 +517,6 @@ void Rover::Log_Write_Vehicle_Startup_Messages() @@ -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;
}

6
APMrover2/system.cpp

@ -249,6 +249,12 @@ void Rover::startup_ground(void) @@ -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);

Loading…
Cancel
Save