diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 8d95af791a..9feddda663 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -87,7 +87,6 @@ public: 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 *str); - void send_text_P(MAV_SEVERITY severity, const prog_char_t *str); void data_stream_send(void); void queued_param_send(); void queued_waypoint_send(); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9348205423..41836e9b45 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -393,7 +393,7 @@ void GCS_MAVLINK::handle_mission_write_partial_list(AP_Mission &mission, mavlink if ((unsigned)packet.start_index > mission.num_commands() || (unsigned)packet.end_index > mission.num_commands() || packet.end_index < packet.start_index) { - send_text_P(MAV_SEVERITY_WARNING,"flight plan update rejected"); + send_text(MAV_SEVERITY_WARNING,"flight plan update rejected"); return; } @@ -630,23 +630,6 @@ GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *str) } } -void -GCS_MAVLINK::send_text_P(MAV_SEVERITY severity, const prog_char_t *str) -{ - mavlink_statustext_t m; - uint8_t i; - memset(m.text, 0, sizeof(m.text)); - for (i=0; icompid, MAV_MISSION_ACCEPTED); - send_text_P(MAV_SEVERITY_WARNING,"flight plan received"); + send_text(MAV_SEVERITY_WARNING,"flight plan received"); waypoint_receiving = false; mission_is_complete = true; // XXX ignores waypoint radius for individual waypoints, can