mirror of https://github.com/ArduPilot/ardupilot
adapt send_text() for typesafe PSTR()
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1799 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
776b9b6f7a
commit
aa91c2c1f2
|
@ -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:
|
||||
|
|
|
@ -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<sizeof(m.text); i++) {
|
||||
m.text[i] = pgm_read_byte(str++);
|
||||
m.text[i] = pgm_read_byte((const prog_char *)str++);
|
||||
}
|
||||
if (i < sizeof(m.text)) m.text[i] = 0;
|
||||
mavlink_send_text(chan, severity, (const char *)m.text);
|
||||
|
|
|
@ -71,7 +71,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.
|
||||
///
|
||||
|
@ -114,7 +114,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);
|
||||
private:
|
||||
void output_HIL();
|
||||
|
|
|
@ -119,7 +119,7 @@ HIL_XPLANE::send_text(uint8_t severity, const char *str)
|
|||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::send_text_P(uint8_t severity, const char *str)
|
||||
HIL_XPLANE::send_text(uint8_t severity, const prog_char_t *str)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue