Browse Source

AP_GPS: canonicalise statustext messages

Use "GPS %d" prefix, where %d is instance+1, to correspond
with parameters
master
Peter Barker 9 years ago
parent
commit
94a5e94ec9
  1. 4
      libraries/AP_GPS/AP_GPS.cpp
  2. 2
      libraries/AP_GPS/AP_GPS_UBLOX.cpp

4
libraries/AP_GPS/AP_GPS.cpp

@ -964,13 +964,13 @@ void AP_GPS::_broadcast_gps_type(const char *type, uint8_t instance, int8_t baud @@ -964,13 +964,13 @@ void AP_GPS::_broadcast_gps_type(const char *type, uint8_t instance, int8_t baud
if (baud_index >= 0) {
hal.util->snprintf(buffer, sizeof(buffer),
"GPS %d: detected as %s at %d baud",
instance,
instance + 1,
type,
_baudrates[baud_index]);
} else {
hal.util->snprintf(buffer, sizeof(buffer),
"GPS %d: detected as %s",
instance,
instance + 1,
type);
}
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, buffer);

2
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -812,7 +812,7 @@ AP_GPS_UBLOX::_parse_gps(void) @@ -812,7 +812,7 @@ AP_GPS_UBLOX::_parse_gps(void)
_have_version = true;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO,
"u-blox %d HW: %s SW: %s",
state.instance,
state.instance + 1,
_buffer.mon_ver.hwVersion,
_buffer.mon_ver.swVersion);
break;

Loading…
Cancel
Save