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_RangeFinder: Notify different alerts #26596

Merged
merged 2 commits into from
Jan 13, 2025
Merged
Show file tree
Hide file tree
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
36 changes: 23 additions & 13 deletions libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m)
#if AP_RANGEFINDER_AINSTEIN_LR_D1_SHOW_MALFUNCTIONS
const uint32_t now_ms = AP_HAL::millis();
if (malfunction_alert_prev != malfunction_alert && now_ms - malfunction_alert_last_send_ms >= 1000) {
report_malfunction(malfunction_alert, malfunction_alert_prev);
malfunction_alert_prev = malfunction_alert;
malfunction_alert_last_send_ms = now_ms;
report_malfunction(malfunction_alert);
}
#endif

Expand Down Expand Up @@ -109,18 +109,28 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m)
}

#if AP_RANGEFINDER_AINSTEIN_LR_D1_SHOW_MALFUNCTIONS
void AP_RangeFinder_Ainstein_LR_D1::report_malfunction(const uint8_t _malfunction_alert_) {
if (_malfunction_alert_ & static_cast<uint8_t>(MalfunctionAlert::Temperature)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RangeFinder: Temperature alert");
}
if (_malfunction_alert_ & static_cast<uint8_t>(MalfunctionAlert::Voltage)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RangeFinder: Voltage alert");
}
if (_malfunction_alert_ & static_cast<uint8_t>(MalfunctionAlert::IFSignalSaturation)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RangeFinder: IF signal saturation alert");
}
if (_malfunction_alert_ & static_cast<uint8_t>(MalfunctionAlert::AltitudeReading)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RangeFinder: Altitude reading overflow alert");
void AP_RangeFinder_Ainstein_LR_D1::report_malfunction(const uint8_t _malfunction_alert_, const uint8_t _malfunction_alert_prev_)
{
static const struct {
MalfunctionAlert bit;
const char *name;
} alerts[] {
{ MalfunctionAlert::Temperature, "Temperature" },
{ MalfunctionAlert::Voltage, "Voltage" },
{ MalfunctionAlert::IFSignalSaturation, "IF signal saturation" },
{ MalfunctionAlert::AltitudeReading, "Attitude reading overflow" },
};

for (const auto &alert : alerts) {
if ((_malfunction_alert_ & uint8_t(alert.bit)) == 0) {
// alert not current
continue;
}
if ((_malfunction_alert_prev_ & uint8_t(alert.bit)) != 0) {
// alert is not new
continue;
}
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RangeFinder: %s alert", alert.name);
}
}
#endif // AP_RANGEFINDER_AINSTEIN_LR_D1_SHOW_MALFUNCTIONS
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class AP_RangeFinder_Ainstein_LR_D1 : public AP_RangeFinder_Backend_Serial
// quality is not available
int8_t get_signal_quality_pct() const override { return signal_quality_pct; };

static void report_malfunction(const uint8_t _malfunction_alert_);
static void report_malfunction(const uint8_t _malfunction_alert_, const uint8_t _malfunction_alert_prev_);

enum class MalfunctionAlert : uint8_t {
Temperature = (1U << 0), // 0x01
Expand Down
Loading