DataFlash: add reason to MODE

This commit is contained in:
Jonathan Challinger 2016-01-25 15:45:27 -08:00 committed by Randy Mackay
parent 1356deab8b
commit a0e291bf89
5 changed files with 9 additions and 7 deletions

View File

@ -187,9 +187,9 @@ void DataFlash_Class::Log_Write_Message(const char *message)
FOR_EACH_BACKEND(Log_Write_Message(message)); FOR_EACH_BACKEND(Log_Write_Message(message));
} }
void DataFlash_Class::Log_Write_Mode(uint8_t mode) void DataFlash_Class::Log_Write_Mode(uint8_t mode, uint8_t reason)
{ {
FOR_EACH_BACKEND(Log_Write_Mode(mode)); FOR_EACH_BACKEND(Log_Write_Mode(mode, reason));
} }
void DataFlash_Class::Log_Write_Parameter(const char *name, float value) void DataFlash_Class::Log_Write_Parameter(const char *name, float value)

View File

@ -121,7 +121,7 @@ public:
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets); void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle); void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
void Log_Write_Compass(const Compass &compass); void Log_Write_Compass(const Compass &compass);
void Log_Write_Mode(uint8_t mode); void Log_Write_Mode(uint8_t mode, uint8_t reason = 0);
void Log_Write_EntireMission(const AP_Mission &mission); void Log_Write_EntireMission(const AP_Mission &mission);
void Log_Write_Mission_Cmd(const AP_Mission &mission, void Log_Write_Mission_Cmd(const AP_Mission &mission,

View File

@ -88,7 +88,7 @@ public:
bool Log_Write_Message(const char *message); bool Log_Write_Message(const char *message);
bool Log_Write_Mission_Cmd(const AP_Mission &mission, bool Log_Write_Mission_Cmd(const AP_Mission &mission,
const AP_Mission::Mission_Command &cmd); const AP_Mission::Mission_Command &cmd);
bool Log_Write_Mode(uint8_t mode);; bool Log_Write_Mode(uint8_t mode, uint8_t reason = 0);
bool Log_Write_Parameter(const char *name, float value); bool Log_Write_Parameter(const char *name, float value);
bool Log_Write_Parameter(const AP_Param *ap, bool Log_Write_Parameter(const AP_Param *ap,
const AP_Param::ParamToken &token, const AP_Param::ParamToken &token,

View File

@ -1687,13 +1687,14 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
} }
// Write a mode packet. // Write a mode packet.
bool DataFlash_Backend::Log_Write_Mode(uint8_t mode) bool DataFlash_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason)
{ {
struct log_Mode pkt = { struct log_Mode pkt = {
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG), LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
mode : mode, mode : mode,
mode_num : mode mode_num : mode,
mode_reason : reason
}; };
return WriteCriticalBlock(&pkt, sizeof(pkt)); return WriteCriticalBlock(&pkt, sizeof(pkt));
} }

View File

@ -445,6 +445,7 @@ struct PACKED log_Mode {
uint64_t time_us; uint64_t time_us;
uint8_t mode; uint8_t mode;
uint8_t mode_num; uint8_t mode_num;
uint8_t mode_reason;
}; };
/* /*
@ -750,7 +751,7 @@ Format characters in the format string for binary log messages
{ LOG_COMPASS_MSG, sizeof(log_Compass), \ { LOG_COMPASS_MSG, sizeof(log_Compass), \
"MAG", "QhhhhhhhhhB", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \ "MAG", "QhhhhhhhhhB", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \
{ LOG_MODE_MSG, sizeof(log_Mode), \ { LOG_MODE_MSG, sizeof(log_Mode), \
"MODE", "QMB", "TimeUS,Mode,ModeNum" }, \ "MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn" }, \
{ LOG_RFND_MSG, sizeof(log_RFND), \ { LOG_RFND_MSG, sizeof(log_RFND), \
"RFND", "QCC", "TimeUS,Dist1,Dist2" }, \ "RFND", "QCC", "TimeUS,Dist1,Dist2" }, \
{ LOG_DF_MAV_STATS, sizeof(log_DF_MAV_Stats), \ { LOG_DF_MAV_STATS, sizeof(log_DF_MAV_Stats), \