mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Sub: Rework log opening/closing logic
We were trying to open logs at >400Hz when logging wasn't available
This commit is contained in:
parent
20f7d75b5a
commit
287f2e3c56
@ -118,12 +118,14 @@ void Sub::init_disarm_motors()
|
|||||||
// reset the mission
|
// reset the mission
|
||||||
mission.reset();
|
mission.reset();
|
||||||
|
|
||||||
// suspend logging
|
|
||||||
if (!DataFlash.log_while_disarmed()) {
|
|
||||||
DataFlash.EnableWrites(false);
|
|
||||||
}
|
|
||||||
DataFlash_Class::instance()->set_vehicle_armed(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
|
// disable gps velocity based centrefugal force compensation
|
||||||
ahrs.set_correct_centrifugal(false);
|
ahrs.set_correct_centrifugal(false);
|
||||||
hal.util->set_soft_armed(false);
|
hal.util->set_soft_armed(false);
|
||||||
|
@ -181,6 +181,10 @@ void Sub::init_ardupilot()
|
|||||||
// init vehicle capabilties
|
// init vehicle capabilties
|
||||||
init_capabilities();
|
init_capabilities();
|
||||||
|
|
||||||
|
if (DataFlash.log_while_disarmed()) {
|
||||||
|
start_logging(); // create a new log if necessary
|
||||||
|
}
|
||||||
|
|
||||||
hal.console->print("\nInit complete");
|
hal.console->print("\nInit complete");
|
||||||
|
|
||||||
// flag that initialisation has completed
|
// flag that initialisation has completed
|
||||||
@ -283,10 +287,7 @@ bool Sub::should_log(uint32_t mask)
|
|||||||
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
bool ret = motors.armed() || DataFlash.log_while_disarmed();
|
bool ret = DataFlash.logging_started() && (motors.armed() || DataFlash.log_while_disarmed());
|
||||||
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
|
||||||
start_logging();
|
|
||||||
}
|
|
||||||
return ret;
|
return ret;
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user