mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_GPS: use mavlink definition to get statustext size
Also, add one for null-termination
This commit is contained in:
parent
c0e03522c6
commit
40daa8e15f
@ -158,14 +158,14 @@ void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) cons
|
|||||||
|
|
||||||
void AP_GPS_Backend::broadcast_gps_type() const
|
void AP_GPS_Backend::broadcast_gps_type() const
|
||||||
{
|
{
|
||||||
char buffer[64];
|
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||||
_detection_message(buffer, sizeof(buffer));
|
_detection_message(buffer, sizeof(buffer));
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, buffer);
|
gcs().send_text(MAV_SEVERITY_INFO, buffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_GPS_Backend::Write_DataFlash_Log_Startup_messages() const
|
void AP_GPS_Backend::Write_DataFlash_Log_Startup_messages() const
|
||||||
{
|
{
|
||||||
char buffer[64];
|
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||||
_detection_message(buffer, sizeof(buffer));
|
_detection_message(buffer, sizeof(buffer));
|
||||||
DataFlash_Class::instance()->Log_Write_Message(buffer);
|
DataFlash_Class::instance()->Log_Write_Message(buffer);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user