Copter: move starting of new logs into DataFlash
This commit is contained in:
parent
a1115ba5d0
commit
e45efeb829
@ -544,11 +544,6 @@ bool AP_Arming_Copter::pre_arm_proximity_check(bool display_failure)
|
||||
// has side-effect that logging is started
|
||||
bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
||||
{
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// start dataflash
|
||||
copter.start_logging();
|
||||
#endif
|
||||
|
||||
// check accels and gyro are healthy
|
||||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_INS)) {
|
||||
//check if accelerometers have calibrated and require reboot
|
||||
|
@ -755,7 +755,6 @@ private:
|
||||
void Log_Write_Beacon();
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page);
|
||||
void start_logging() ;
|
||||
void load_parameters(void);
|
||||
void convert_pid_parameters(void);
|
||||
void userhook_init();
|
||||
|
@ -917,22 +917,6 @@ void Copter::Log_Write_Vehicle_Startup_Messages()
|
||||
}
|
||||
|
||||
|
||||
void Copter::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 Copter::log_init(void)
|
||||
{
|
||||
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
@ -989,7 +973,6 @@ void Copter::Log_Write_Heli() {}
|
||||
void Copter::Log_Write_Optflow() {}
|
||||
#endif
|
||||
|
||||
void Copter::start_logging() {}
|
||||
void Copter::log_init(void) {}
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
|
@ -491,11 +491,8 @@ void Copter::check_usb_mux(void)
|
||||
bool Copter::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
|
||||
|
Loading…
Reference in New Issue
Block a user