Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Baro: replace gcs().send_text with GCS_SEND_TEXT #27797

Merged
merged 1 commit into from
Aug 9, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 6 additions & 12 deletions libraries/AP_Baro/AP_Baro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -260,12 +260,6 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
// singleton instance
AP_Baro *AP_Baro::_singleton;

#if HAL_GCS_ENABLED
#define BARO_SEND_TEXT(severity, format, args...) GCS_SEND_TEXT(severity, format, ##args)
#else
#define BARO_SEND_TEXT(severity, format, args...)
#endif

/*
AP_Baro constructor
*/
Expand All @@ -288,7 +282,7 @@ void AP_Baro::calibrate(bool save)
}

if (hal.util->was_watchdog_reset()) {
BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset");
return;
}

Expand All @@ -300,12 +294,12 @@ void AP_Baro::calibrate(bool save)

#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration");
return;
}
#endif

BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer");

// reset the altitude offset when we calibrate. The altitude
// offset is supposed to be for within a flight
Expand Down Expand Up @@ -364,7 +358,7 @@ void AP_Baro::calibrate(bool save)
uint8_t num_calibrated = 0;
for (uint8_t i=0; i<_num_sensors; i++) {
if (sensors[i].calibrated) {
BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1);
num_calibrated++;
}
}
Expand Down Expand Up @@ -980,15 +974,15 @@ void AP_Baro::update_field_elevation(void)
} else {
_field_elevation.set(_field_elevation_active);
_field_elevation.notify();
BARO_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed");
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed");
}
}
}
if (new_field_elev && !armed) {
_field_elevation_last_ms = now_ms;
AP::ahrs().resetHeightDatum();
update_calibration();
BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active);
}
#endif
}
Expand Down
Loading