mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_GPS: eliminate GCS_MAVLINK::send_statustext_all
This commit is contained in:
parent
31ffc83f64
commit
76847a2487
@ -929,7 +929,7 @@ void AP_GPS::broadcast_first_configuration_failure_reason(void) const
|
||||
{
|
||||
uint8_t unconfigured = first_unconfigured_gps();
|
||||
if (drivers[unconfigured] == nullptr) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
|
||||
} else {
|
||||
drivers[unconfigured]->broadcast_configuration_failure_reason();
|
||||
}
|
||||
|
@ -319,13 +319,13 @@ void AP_GPS_SBF::broadcast_configuration_failure_reason(void) const
|
||||
{
|
||||
if (gps._raw_data) {
|
||||
if (!(RxState & SBF_DISK_MOUNTED)){
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: SBF disk is not mounted", state.instance + 1);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF disk is not mounted", state.instance + 1);
|
||||
}
|
||||
else if (RxState & SBF_DISK_FULL) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: SBF disk is full", state.instance + 1);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF disk is full", state.instance + 1);
|
||||
}
|
||||
else if (!(RxState & SBF_DISK_ACTIVITY)) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: SBF is not currently logging", state.instance + 1);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF is not currently logging", state.instance + 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -51,7 +51,7 @@ do { \
|
||||
#if SBP_INFOREPORTING
|
||||
# define Info(fmt, args ...) \
|
||||
do { \
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, fmt "\n", ## args); \
|
||||
gcs().send_text(MAV_SEVERITY_INFO, fmt "\n", ## args); \
|
||||
} while(0)
|
||||
#else
|
||||
# define Info(fmt, args ...)
|
||||
|
@ -814,7 +814,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
_have_version = true;
|
||||
strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
|
||||
strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO,
|
||||
gcs().send_text(MAV_SEVERITY_INFO,
|
||||
"u-blox %d HW: %s SW: %s",
|
||||
state.instance + 1,
|
||||
_version.hwVersion,
|
||||
@ -976,7 +976,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
|
||||
break;
|
||||
case 4:
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO,
|
||||
gcs().send_text(MAV_SEVERITY_INFO,
|
||||
"Unexpected state %d", _buffer.pvt.flags);
|
||||
state.status = AP_GPS::GPS_OK_FIX_3D;
|
||||
break;
|
||||
@ -1195,7 +1195,7 @@ AP_GPS_UBLOX::_save_cfg()
|
||||
_send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
|
||||
_last_cfg_sent_time = AP_HAL::millis();
|
||||
_num_cfg_save_tries++;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO,
|
||||
gcs().send_text(MAV_SEVERITY_INFO,
|
||||
"GPS: u-blox %d saving config",
|
||||
state.instance + 1);
|
||||
}
|
||||
@ -1299,7 +1299,7 @@ void
|
||||
AP_GPS_UBLOX::broadcast_configuration_failure_reason(void) const {
|
||||
for (uint8_t i = 0; i < ARRAY_SIZE(reasons); i++) {
|
||||
if (_unconfigured_messages & (1 << i)) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: u-blox %s configuration 0x%02x",
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: u-blox %s configuration 0x%02x",
|
||||
state.instance +1, reasons[i], _unconfigured_messages);
|
||||
break;
|
||||
}
|
||||
|
@ -24,7 +24,7 @@
|
||||
# define Debug(fmt, args ...)
|
||||
#endif
|
||||
|
||||
#include <GCS_MAVLink/GCS.h> // for send_statustext_all
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -160,7 +160,7 @@ void AP_GPS_Backend::broadcast_gps_type() const
|
||||
{
|
||||
char buffer[64];
|
||||
_detection_message(buffer, sizeof(buffer));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, buffer);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, buffer);
|
||||
}
|
||||
|
||||
void AP_GPS_Backend::Write_DataFlash_Log_Startup_messages() const
|
||||
|
Loading…
Reference in New Issue
Block a user