mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: make send_text and send_textv const
This commit is contained in:
parent
c3f53c55f6
commit
a0c80a0b3b
|
@ -121,8 +121,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(MAV_SEVERITY severity, const char *fmt, ...);
|
||||
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
||||
void send_text(MAV_SEVERITY severity, const char *fmt, ...) const;
|
||||
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) const;
|
||||
void queued_param_send();
|
||||
void queued_mission_request_send();
|
||||
// packetReceived is called on any successful decode of a mavlink message
|
||||
|
|
|
@ -686,13 +686,13 @@ void GCS_MAVLINK::handle_param_value(mavlink_message_t *msg)
|
|||
mount->handle_param_value(msg);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
||||
void GCS_MAVLINK::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) const
|
||||
{
|
||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||
hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
|
||||
gcs().send_statustext(severity, (1<<chan), text);
|
||||
}
|
||||
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
||||
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) const
|
||||
{
|
||||
va_list arg_list;
|
||||
va_start(arg_list, fmt);
|
||||
|
|
Loading…
Reference in New Issue