Browse Source

GCS_Common: accept any type of severity, not just the old enum

mission-4.1.18
squilter 10 years ago committed by Randy Mackay
parent
commit
9d3a906602
  1. 4
      libraries/GCS_MAVLink/GCS.h
  2. 6
      libraries/GCS_MAVLink/GCS_Common.cpp

4
libraries/GCS_MAVLink/GCS.h

@ -84,8 +84,8 @@ public: @@ -84,8 +84,8 @@ public:
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
void send_message(enum ap_message id);
void send_text(gcs_severity severity, const char *str);
void send_text_P(gcs_severity severity, const prog_char_t *str);
void send_text(uint8_t severity, const char *str);
void send_text_P(uint8_t severity, const prog_char_t *str);
void data_stream_send(void);
void queued_param_send();
void queued_waypoint_send();

6
libraries/GCS_MAVLink/GCS_Common.cpp

@ -601,9 +601,9 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *Data @@ -601,9 +601,9 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *Data
void
GCS_MAVLINK::send_text(gcs_severity severity, const char *str)
GCS_MAVLINK::send_text(uint8_t severity, const char *str)
{
if (severity != SEVERITY_LOW &&
if (severity < MAV_SEVERITY_WARNING &&
comm_get_txspace(chan) >=
MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_STATUSTEXT_LEN) {
// send immediately
@ -618,7 +618,7 @@ GCS_MAVLINK::send_text(gcs_severity severity, const char *str) @@ -618,7 +618,7 @@ GCS_MAVLINK::send_text(gcs_severity severity, const char *str)
}
void
GCS_MAVLINK::send_text_P(gcs_severity severity, const prog_char_t *str)
GCS_MAVLINK::send_text_P(uint8_t severity, const prog_char_t *str)
{
mavlink_statustext_t m;
uint8_t i;

Loading…
Cancel
Save