diff --git a/ArduPlane/GCS.h b/ArduPlane/GCS.h index 18f29fb803..3fba61c76b 100644 --- a/ArduPlane/GCS.h +++ b/ArduPlane/GCS.h @@ -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(); diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 182e035148..3bb1d91d83 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -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); diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index e7d9d88505..36d0475f71 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -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(" Missed WP")); + gcs_send_text_P(SEVERITY_MEDIUM,PSTR("Missed WP")); return true; } return false; diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index d43f4dc8bf..5e6eae62f1 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -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