Sub: move starting of new logs into DataFlash

This commit is contained in:
Peter Barker 2017-06-30 21:35:49 +10:00 committed by Francisco Ferreira
parent e45efeb829
commit 342d95ad2f
4 changed files with 2 additions and 28 deletions

View File

@ -466,22 +466,6 @@ void Sub::Log_Write_Vehicle_Startup_Messages()
}
void Sub::start_logging()
{
if (g.log_bitmask == 0) {
return;
}
if (DataFlash.in_log_download()) {
return;
}
ap.logging_started = true;
// dataflash may have stopped logging - when we get_log_data,
// for example. Always try to restart:
DataFlash.StartUnstartedLogging();
}
void Sub::log_init(void)
{
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
@ -515,7 +499,6 @@ void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target
void Sub::Log_Write_Optflow() {}
#endif
void Sub::start_logging() {}
void Sub::log_init(void) {}
#endif // LOGGING_ENABLED

View File

@ -515,7 +515,6 @@ private:
void Log_Sensor_Health();
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
void Log_Write_Vehicle_Startup_Messages();
void start_logging() ;
void load_parameters(void);
void userhook_init();
void userhook_FastLoop();

View File

@ -12,7 +12,6 @@ void Sub::enable_motor_output()
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
bool Sub::init_arm_motors(bool arming_from_gcs)
{
start_logging();
static bool in_arm_motors = false;
// exit immediately if already in this function

View File

@ -189,10 +189,6 @@ void Sub::init_ardupilot()
// init vehicle capabilties
init_capabilities();
if (DataFlash.log_while_disarmed()) {
start_logging(); // create a new log if necessary
}
// disable safety if requested
BoardConfig.init_safety();
@ -295,11 +291,8 @@ bool Sub::optflow_position_ok()
bool Sub::should_log(uint32_t mask)
{
#if LOGGING_ENABLED == ENABLED
if (!DataFlash.should_log(mask)) {
return false;
}
start_logging();
return true;
ap.logging_started = DataFlash.logging_started();
return DataFlash.should_log(mask);
#else
return false;
#endif