mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_FrSky_Telem: use constant strings in message queueing
This commit is contained in:
parent
183283ba07
commit
62388fc991
@ -495,7 +495,7 @@ uint32_t AP_Frsky_Telem::get_next_msg_chunk(void)
|
||||
void AP_Frsky_Telem::queue_message(MAV_SEVERITY severity, const char *text)
|
||||
{
|
||||
_msg.data[_msg.queued_idx].severity = severity;
|
||||
strncpy((char *)_msg.data[_msg.queued_idx].text, text, 50);
|
||||
_msg.data[_msg.queued_idx].text = text;
|
||||
_msg.queued_idx = (_msg.queued_idx + 1) % MSG_BUFFER_LENGTH;
|
||||
}
|
||||
|
||||
|
@ -134,7 +134,10 @@ public:
|
||||
|
||||
struct msg_t
|
||||
{
|
||||
mavlink_statustext_t data[MSG_BUFFER_LENGTH];
|
||||
struct {
|
||||
const char *text;
|
||||
uint8_t severity;
|
||||
} data[MSG_BUFFER_LENGTH];
|
||||
uint8_t queued_idx;
|
||||
uint8_t sent_idx;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user