mirror of https://github.com/ArduPilot/ardupilot
Added some useful error messages.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@823 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
9e6fcded41
commit
d8b3dd9aa1
|
@ -102,7 +102,7 @@ BinComm::update(void)
|
|||
{
|
||||
char text[50];
|
||||
strncpy(text,"buffer overflow",50);
|
||||
send_msg_status_text(1,text);
|
||||
send_msg_status_text(SEVERITY_LOW,text);
|
||||
}
|
||||
|
||||
while (count--)
|
||||
|
@ -219,6 +219,12 @@ BinComm::_decode(uint8_t inByte)
|
|||
// dont' acknowledge an acknowledgement, will echo infinetly
|
||||
if (_messageID != MSG_ACKNOWLEDGE) send_msg_acknowledge(_messageID,_sumA,_sumB);
|
||||
}
|
||||
else
|
||||
{
|
||||
char str[50];
|
||||
sprintf(str,"<bincomm> unhandled messageID:%x",_messageID);
|
||||
send_msg_status_text(SEVERITY_LOW,str);
|
||||
}
|
||||
} else {
|
||||
badMessagesReceived++;
|
||||
}
|
||||
|
|
|
@ -185,6 +185,15 @@ public:
|
|||
///
|
||||
//@{
|
||||
|
||||
/// Message serverities
|
||||
enum severities
|
||||
{
|
||||
SEVERITY_LOW = 1,
|
||||
SEVERITY_MEDIUM = 2,
|
||||
SEVERITY_HIGH = 3,
|
||||
SEVERITY_CRITICAL = 4,
|
||||
};
|
||||
|
||||
/// Variables defined
|
||||
/// XXX these should probably be handled by the database/MIB?
|
||||
enum variableID {
|
||||
|
|
|
@ -59,11 +59,17 @@
|
|||
|
||||
#
|
||||
# Acknowledge message
|
||||
#
|
||||
# Required by protocol, don't change
|
||||
message 0x00 MSG_ACKNOWLEDGE
|
||||
uint8_t msgID
|
||||
uint8_t sum1
|
||||
uint8_t sum2
|
||||
#
|
||||
# Text status message
|
||||
# Required by protocol, don't change
|
||||
message 0x05 MSG_STATUS_TEXT
|
||||
uint8_t severity
|
||||
char text 50
|
||||
|
||||
#
|
||||
# System heartbeat
|
||||
|
@ -100,13 +106,6 @@ message 0x04 MSG_PRESSURE
|
|||
int32_t pressureAltitude
|
||||
int16_t airSpeed
|
||||
|
||||
#
|
||||
# Text status message
|
||||
#
|
||||
message 0x05 MSG_STATUS_TEXT
|
||||
uint8_t severity
|
||||
char text 50
|
||||
|
||||
#
|
||||
# Algorithm performance report
|
||||
#
|
||||
|
|
|
@ -47,6 +47,43 @@ unpack_msg_acknowledge(
|
|||
};
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/// @name MSG_STATUS_TEXT
|
||||
//@{
|
||||
|
||||
/// Structure describing the payload section of the MSG_STATUS_TEXT message
|
||||
struct msg_status_text {
|
||||
uint8_t severity;
|
||||
char text[50];
|
||||
};
|
||||
|
||||
/// Send a MSG_STATUS_TEXT message
|
||||
inline void
|
||||
send_msg_status_text(
|
||||
const uint8_t severity,
|
||||
const char (&text)[50])
|
||||
{
|
||||
uint8_t *__p = &_encodeBuf.payload[0];
|
||||
_pack(__p, severity);
|
||||
_pack(__p, text, 50);
|
||||
_encodeBuf.header.length = 51;
|
||||
_encodeBuf.header.messageID = MSG_STATUS_TEXT;
|
||||
_encodeBuf.header.messageVersion = MSG_VERSION_1;
|
||||
_sendMessage();
|
||||
};
|
||||
|
||||
/// Unpack a MSG_STATUS_TEXT message
|
||||
inline void
|
||||
unpack_msg_status_text(
|
||||
uint8_t &severity,
|
||||
char (&text)[50])
|
||||
{
|
||||
uint8_t *__p = &_decodeBuf.payload[0];
|
||||
_unpack(__p, severity);
|
||||
_unpack(__p, text, 50);
|
||||
};
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/// @name MSG_HEARTBEAT
|
||||
//@{
|
||||
|
@ -230,43 +267,6 @@ unpack_msg_pressure(
|
|||
};
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/// @name MSG_STATUS_TEXT
|
||||
//@{
|
||||
|
||||
/// Structure describing the payload section of the MSG_STATUS_TEXT message
|
||||
struct msg_status_text {
|
||||
uint8_t severity;
|
||||
char text[50];
|
||||
};
|
||||
|
||||
/// Send a MSG_STATUS_TEXT message
|
||||
inline void
|
||||
send_msg_status_text(
|
||||
const uint8_t severity,
|
||||
const char (&text)[50])
|
||||
{
|
||||
uint8_t *__p = &_encodeBuf.payload[0];
|
||||
_pack(__p, severity);
|
||||
_pack(__p, text, 50);
|
||||
_encodeBuf.header.length = 51;
|
||||
_encodeBuf.header.messageID = MSG_STATUS_TEXT;
|
||||
_encodeBuf.header.messageVersion = MSG_VERSION_1;
|
||||
_sendMessage();
|
||||
};
|
||||
|
||||
/// Unpack a MSG_STATUS_TEXT message
|
||||
inline void
|
||||
unpack_msg_status_text(
|
||||
uint8_t &severity,
|
||||
char (&text)[50])
|
||||
{
|
||||
uint8_t *__p = &_decodeBuf.payload[0];
|
||||
_unpack(__p, severity);
|
||||
_unpack(__p, text, 50);
|
||||
};
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/// @name MSG_PERF_REPORT
|
||||
//@{
|
||||
|
|
Loading…
Reference in New Issue