mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Fix logging bug where only one log was created after first arm
This commit is contained in:
parent
8b3c414ca7
commit
01e01d1df9
@ -468,12 +468,17 @@ void Sub::Log_Write_Vehicle_Startup_Messages()
|
|||||||
// start a new log
|
// start a new log
|
||||||
void Sub::start_logging()
|
void Sub::start_logging()
|
||||||
{
|
{
|
||||||
if (g.log_bitmask != 0) {
|
if (g.log_bitmask != 0 && !in_log_download) {
|
||||||
if (!ap.logging_started) {
|
if (!ap.logging_started) {
|
||||||
ap.logging_started = true;
|
ap.logging_started = true;
|
||||||
DataFlash.set_mission(&mission);
|
DataFlash.set_mission(&mission);
|
||||||
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
|
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
|
||||||
DataFlash.StartNewLog();
|
DataFlash.StartNewLog();
|
||||||
|
} else if (!DataFlash.logging_started()) {
|
||||||
|
hal.console->println("Starting new log");
|
||||||
|
// dataflash may have stopped logging - when we get_log_data,
|
||||||
|
// for example. Try to restart:
|
||||||
|
DataFlash.StartNewLog();
|
||||||
}
|
}
|
||||||
// enable writes
|
// enable writes
|
||||||
DataFlash.EnableWrites(true);
|
DataFlash.EnableWrites(true);
|
||||||
|
@ -12,6 +12,7 @@ void Sub::enable_motor_output()
|
|||||||
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
// 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)
|
bool Sub::init_arm_motors(bool arming_from_gcs)
|
||||||
{
|
{
|
||||||
|
start_logging();
|
||||||
static bool in_arm_motors = false;
|
static bool in_arm_motors = false;
|
||||||
|
|
||||||
// exit immediately if already in this function
|
// exit immediately if already in this function
|
||||||
@ -27,6 +28,9 @@ bool Sub::init_arm_motors(bool arming_from_gcs)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// let dataflash know that we're armed (it may open logs e.g.)
|
||||||
|
DataFlash_Class::instance()->set_vehicle_armed(true);
|
||||||
|
|
||||||
// disable cpu failsafe because initialising everything takes a while
|
// disable cpu failsafe because initialising everything takes a while
|
||||||
mainloop_failsafe_disable();
|
mainloop_failsafe_disable();
|
||||||
|
|
||||||
@ -118,6 +122,7 @@ void Sub::init_disarm_motors()
|
|||||||
if (!DataFlash.log_while_disarmed()) {
|
if (!DataFlash.log_while_disarmed()) {
|
||||||
DataFlash.EnableWrites(false);
|
DataFlash.EnableWrites(false);
|
||||||
}
|
}
|
||||||
|
DataFlash_Class::instance()->set_vehicle_armed(false);
|
||||||
|
|
||||||
// disable gps velocity based centrefugal force compensation
|
// disable gps velocity based centrefugal force compensation
|
||||||
ahrs.set_correct_centrifugal(false);
|
ahrs.set_correct_centrifugal(false);
|
||||||
|
Loading…
Reference in New Issue
Block a user