Plane: move init of DataFlash references into vehicle init

It is possible to start a log before the existing codepath is crossed.
This commit is contained in:
Peter Barker 2017-05-01 16:08:35 +10:00 committed by Francisco Ferreira
parent 069e0d1973
commit 084242cf03
2 changed files with 6 additions and 5 deletions

View File

@ -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();
}

View File

@ -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();