Browse Source

DataFlash: add reason to MODE

master
Jonathan Challinger 9 years ago committed by Randy Mackay
parent
commit
a0e291bf89
  1. 4
      libraries/DataFlash/DataFlash.cpp
  2. 2
      libraries/DataFlash/DataFlash.h
  3. 2
      libraries/DataFlash/DataFlash_Backend.h
  4. 5
      libraries/DataFlash/LogFile.cpp
  5. 3
      libraries/DataFlash/LogStructure.h

4
libraries/DataFlash/DataFlash.cpp

@ -187,9 +187,9 @@ void DataFlash_Class::Log_Write_Message(const char *message) @@ -187,9 +187,9 @@ void DataFlash_Class::Log_Write_Message(const char *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)

2
libraries/DataFlash/DataFlash.h

@ -121,7 +121,7 @@ public: @@ -121,7 +121,7 @@ public:
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
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_Mission_Cmd(const AP_Mission &mission,

2
libraries/DataFlash/DataFlash_Backend.h

@ -88,7 +88,7 @@ public: @@ -88,7 +88,7 @@ public:
bool Log_Write_Message(const char *message);
bool Log_Write_Mission_Cmd(const AP_Mission &mission,
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 AP_Param *ap,
const AP_Param::ParamToken &token,

5
libraries/DataFlash/LogFile.cpp

@ -1687,13 +1687,14 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass) @@ -1687,13 +1687,14 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
}
// 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 = {
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
time_us : AP_HAL::micros64(),
mode : mode,
mode_num : mode
mode_num : mode,
mode_reason : reason
};
return WriteCriticalBlock(&pkt, sizeof(pkt));
}

3
libraries/DataFlash/LogStructure.h

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

Loading…
Cancel
Save