AP_GPS: canonicalise statustext messages

Use "GPS %d" prefix, where %d is instance+1, to correspond
with parameters
This commit is contained in:
Peter Barker 2016-08-02 17:31:11 +10:00
parent 4334a92ac9
commit 94a5e94ec9
2 changed files with 3 additions and 3 deletions

View File

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

View File

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