mirror of https://github.com/ArduPilot/ardupilot
Rover: always log MODE and include reason when logging is enabled
This commit is contained in:
parent
e340fac2e0
commit
f7d07fc146
|
@ -62,7 +62,7 @@ enum mode {
|
|||
#define MASK_LOG_PM (1<<3)
|
||||
#define MASK_LOG_CTUN (1<<4)
|
||||
#define MASK_LOG_NTUN (1<<5)
|
||||
#define MASK_LOG_MODE (1<<6)
|
||||
//#define MASK_LOG_MODE (1<<6) // no longer used
|
||||
#define MASK_LOG_IMU (1<<7)
|
||||
#define MASK_LOG_CMD (1<<8)
|
||||
#define MASK_LOG_CURRENT (1<<9)
|
||||
|
|
|
@ -232,10 +232,8 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
|
|||
|
||||
old_mode.exit();
|
||||
|
||||
if (should_log(MASK_LOG_MODE)) {
|
||||
control_mode_reason = reason;
|
||||
DataFlash.Log_Write_Mode(control_mode->mode_number(), reason);
|
||||
}
|
||||
DataFlash.Log_Write_Mode(control_mode->mode_number(), control_mode_reason);
|
||||
|
||||
notify_mode((enum mode)control_mode->mode_number());
|
||||
return true;
|
||||
|
|
Loading…
Reference in New Issue