diff --git a/ArduCopterMega/GCS.h b/ArduCopterMega/GCS.h index 4fcdb75bab..8276f41fe4 100644 --- a/ArduCopterMega/GCS.h +++ b/ArduCopterMega/GCS.h @@ -70,7 +70,7 @@ public: /// @param severity A value describing the importance of the message. /// @param str The text to be sent. /// - void send_text_P(uint8_t severity, const char *str) {} + void send_text_P(uint8_t severity, const prog_char_t *str) {} /// Send acknowledgement for a message. /// @@ -140,7 +140,7 @@ public: void init(BetterStream *port); void send_message(uint8_t id, uint32_t param = 0); void send_text(uint8_t severity, const char *str); - void send_text_P(uint8_t severity, const char *str); + void send_text_P(uint8_t severity, const prog_char_t *str); void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2); void data_stream_send(uint16_t freqMin, uint16_t freqMax); private: diff --git a/ArduCopterMega/GCS_Mavlink.pde b/ArduCopterMega/GCS_Mavlink.pde index f03106e033..708fcbb4fd 100644 --- a/ArduCopterMega/GCS_Mavlink.pde +++ b/ArduCopterMega/GCS_Mavlink.pde @@ -117,12 +117,12 @@ GCS_MAVLINK::send_text(uint8_t severity, const char *str) } void -GCS_MAVLINK::send_text_P(uint8_t severity, const char *str) +GCS_MAVLINK::send_text_P(uint8_t severity, const prog_char_t *str) { mavlink_statustext_t m; uint8_t i; for (i=0; i