Browse Source

Plane: move init of DataFlash references into vehicle init

It is possible to start a log before the existing codepath is crossed.
master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
084242cf03
  1. 5
      ArduPlane/Log.cpp
  2. 6
      ArduPlane/system.cpp

5
ArduPlane/Log.cpp

@ -561,11 +561,6 @@ void Plane::Log_Write_Vehicle_Startup_Messages() @@ -561,11 +561,6 @@ void Plane::Log_Write_Vehicle_Startup_Messages()
// start a new log
void Plane::start_logging()
{
DataFlash.set_mission(&mission);
DataFlash.setVehicle_Startup_Log_Writer(
FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void)
);
DataFlash.StartNewLog();
}

6
ArduPlane/system.cpp

@ -297,6 +297,12 @@ void Plane::startup_ground(void) @@ -297,6 +297,12 @@ void Plane::startup_ground(void)
// initialise mission library
mission.init();
// initialise DataFlash library
DataFlash.set_mission(&mission);
DataFlash.setVehicle_Startup_Log_Writer(
FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void)
);
// reset last heartbeat time, so we don't trigger failsafe on slow
// startup
failsafe.last_heartbeat_ms = millis();

Loading…
Cancel
Save