Sub: Rework log opening/closing logic

We were trying to open logs at >400Hz when logging wasn't available
This commit is contained in:
Jacob Walser 2017-04-17 10:55:18 -04:00
parent 20f7d75b5a
commit 287f2e3c56
2 changed files with 11 additions and 8 deletions

View File

@ -118,12 +118,14 @@ void Sub::init_disarm_motors()
// reset the mission
mission.reset();
// suspend logging
if (!DataFlash.log_while_disarmed()) {
DataFlash.EnableWrites(false);
}
DataFlash_Class::instance()->set_vehicle_armed(false);
if (DataFlash.log_while_disarmed()) {
start_logging(); // create a new log if necessary
} else {
DataFlash.EnableWrites(false); // suspend logging
}
// disable gps velocity based centrefugal force compensation
ahrs.set_correct_centrifugal(false);
hal.util->set_soft_armed(false);

View File

@ -181,6 +181,10 @@ void Sub::init_ardupilot()
// init vehicle capabilties
init_capabilities();
if (DataFlash.log_while_disarmed()) {
start_logging(); // create a new log if necessary
}
hal.console->print("\nInit complete");
// flag that initialisation has completed
@ -283,10 +287,7 @@ bool Sub::should_log(uint32_t mask)
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
return false;
}
bool ret = motors.armed() || DataFlash.log_while_disarmed();
if (ret && !DataFlash.logging_started() && !in_log_download) {
start_logging();
}
bool ret = DataFlash.logging_started() && (motors.armed() || DataFlash.log_while_disarmed());
return ret;
#else
return false;