mirror of https://github.com/ArduPilot/ardupilot
added gcs_severity enum
this makes it harder to mixup defines
This commit is contained in:
parent
4e346a0cc5
commit
8f604a1035
|
@ -63,14 +63,14 @@ public:
|
|||
/// @param severity A value describing the importance of the message.
|
||||
/// @param str The text to be sent.
|
||||
///
|
||||
void send_text(uint8_t severity, const char *str) {}
|
||||
void send_text(gcs_severity severity, const char *str) {}
|
||||
|
||||
/// Send a text message with a PSTR()
|
||||
///
|
||||
/// @param severity A value describing the importance of the message.
|
||||
/// @param str The text to be sent.
|
||||
///
|
||||
void send_text(uint8_t severity, const prog_char_t *str) {}
|
||||
void send_text(gcs_severity severity, const prog_char_t *str) {}
|
||||
|
||||
// test if frequency within range requested for loop
|
||||
// used by data_stream_send
|
||||
|
@ -107,8 +107,8 @@ public:
|
|||
void update(void);
|
||||
void init(FastSerial *port);
|
||||
void send_message(enum ap_message id);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void send_text(uint8_t severity, const prog_char_t *str);
|
||||
void send_text(gcs_severity severity, const char *str);
|
||||
void send_text(gcs_severity severity, const prog_char_t *str);
|
||||
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
|
||||
void queued_param_send();
|
||||
void queued_waypoint_send();
|
||||
|
|
|
@ -457,7 +457,7 @@ static void mavlink_send_message(mavlink_channel_t chan, enum ap_message id, uin
|
|||
}
|
||||
}
|
||||
|
||||
void mavlink_send_text(mavlink_channel_t chan, uint8_t severity, const char *str)
|
||||
void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char *str)
|
||||
{
|
||||
if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) {
|
||||
// don't send status MAVLink messages for 1 second after
|
||||
|
@ -607,13 +607,13 @@ GCS_MAVLINK::send_message(enum ap_message id)
|
|||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_text(uint8_t severity, const char *str)
|
||||
GCS_MAVLINK::send_text(gcs_severity severity, const char *str)
|
||||
{
|
||||
mavlink_send_text(chan,severity,str);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_text(uint8_t severity, const prog_char_t *str)
|
||||
GCS_MAVLINK::send_text(gcs_severity severity, const prog_char_t *str)
|
||||
{
|
||||
mavlink_statustext_t m;
|
||||
uint8_t i;
|
||||
|
@ -1581,13 +1581,13 @@ static void gcs_update(void)
|
|||
gcs3.update();
|
||||
}
|
||||
|
||||
static void gcs_send_text(uint8_t severity, const char *str)
|
||||
static void gcs_send_text(gcs_severity severity, const char *str)
|
||||
{
|
||||
gcs0.send_text(severity, str);
|
||||
gcs3.send_text(severity, str);
|
||||
}
|
||||
|
||||
static void gcs_send_text_P(uint8_t severity, const prog_char_t *str)
|
||||
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
|
||||
{
|
||||
gcs0.send_text(severity, str);
|
||||
gcs3.send_text(severity, str);
|
||||
|
|
|
@ -326,7 +326,7 @@ static bool verify_nav_wp()
|
|||
// add in a more complex case
|
||||
// Doug to do
|
||||
if(loiter_sum > 300){
|
||||
gcs_send_text_P(SEVERITY_MEDIUM,PSTR("<verify_must: MAV_CMD_NAV_WAYPOINT> Missed WP"));
|
||||
gcs_send_text_P(SEVERITY_MEDIUM,PSTR("Missed WP"));
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
|
|
@ -131,10 +131,12 @@ enum ap_message {
|
|||
MSG_RETRY_DEFERRED // this must be last
|
||||
};
|
||||
|
||||
#define SEVERITY_LOW 1
|
||||
#define SEVERITY_MEDIUM 2
|
||||
#define SEVERITY_HIGH 3
|
||||
#define SEVERITY_CRITICAL 4
|
||||
enum gcs_severity {
|
||||
SEVERITY_LOW=1,
|
||||
SEVERITY_MEDIUM,
|
||||
SEVERITY_HIGH,
|
||||
SEVERITY_CRITICAL
|
||||
};
|
||||
|
||||
// Logging parameters
|
||||
#define LOG_INDEX_MSG 0xF0
|
||||
|
|
Loading…
Reference in New Issue