Copter: fix startup logging
Removed potentially endless loop caused by start_logging calling Log_Write_Startup which called should_log which could then call start_logging. Moved disarm event logging above motors disarm so it is logged
This commit is contained in:
parent
14561f04b0
commit
4e3d0ae0c1
@ -448,11 +448,6 @@ void Copter::Log_Write_Startup()
|
|||||||
time_us : hal.scheduler->micros64()
|
time_us : hal.scheduler->micros64()
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
|
||||||
// write all commands to the dataflash as well
|
|
||||||
if (should_log(MASK_LOG_CMD)) {
|
|
||||||
DataFlash.Log_Write_EntireMission(mission);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Event {
|
struct PACKED log_Event {
|
||||||
@ -755,6 +750,11 @@ void Copter::start_logging()
|
|||||||
|
|
||||||
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
|
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
|
||||||
|
|
||||||
|
// write mission commands
|
||||||
|
if (MASK_LOG_CMD & g.log_bitmask) {
|
||||||
|
DataFlash.Log_Write_EntireMission(mission);
|
||||||
|
}
|
||||||
|
|
||||||
Log_Write_Startup();
|
Log_Write_Startup();
|
||||||
|
|
||||||
// log the flight mode
|
// log the flight mode
|
||||||
|
@ -822,9 +822,6 @@ void Copter::init_disarm_motors()
|
|||||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// send disarm command to motors
|
|
||||||
motors.armed(false);
|
|
||||||
|
|
||||||
// save compass offsets learned by the EKF
|
// save compass offsets learned by the EKF
|
||||||
Vector3f magOffsets;
|
Vector3f magOffsets;
|
||||||
if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) {
|
if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) {
|
||||||
@ -840,12 +837,15 @@ void Copter::init_disarm_motors()
|
|||||||
set_land_complete(true);
|
set_land_complete(true);
|
||||||
set_land_complete_maybe(true);
|
set_land_complete_maybe(true);
|
||||||
|
|
||||||
// reset the mission
|
|
||||||
mission.reset();
|
|
||||||
|
|
||||||
// log disarm to the dataflash
|
// log disarm to the dataflash
|
||||||
Log_Write_Event(DATA_DISARMED);
|
Log_Write_Event(DATA_DISARMED);
|
||||||
|
|
||||||
|
// send disarm command to motors
|
||||||
|
motors.armed(false);
|
||||||
|
|
||||||
|
// reset the mission
|
||||||
|
mission.reset();
|
||||||
|
|
||||||
// suspend logging
|
// suspend logging
|
||||||
if (!(g.log_bitmask & MASK_LOG_WHEN_DISARMED)) {
|
if (!(g.log_bitmask & MASK_LOG_WHEN_DISARMED)) {
|
||||||
DataFlash.EnableWrites(false);
|
DataFlash.EnableWrites(false);
|
||||||
|
@ -255,10 +255,6 @@ void Copter::init_ardupilot()
|
|||||||
|
|
||||||
startup_ground(true);
|
startup_ground(true);
|
||||||
|
|
||||||
#if LOGGING_ENABLED == ENABLED
|
|
||||||
Log_Write_Startup();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// we don't want writes to the serial port to cause us to pause
|
// we don't want writes to the serial port to cause us to pause
|
||||||
// mid-flight, so set the serial ports non-blocking once we are
|
// mid-flight, so set the serial ports non-blocking once we are
|
||||||
// ready to fly
|
// ready to fly
|
||||||
|
Loading…
Reference in New Issue
Block a user