mirror of https://github.com/ArduPilot/ardupilot
AP_Gernerator: IE 2400: MAV_SEVERITY level depends on error code
This commit is contained in:
parent
cb807934ee
commit
3e083e5ceb
|
@ -562,4 +562,18 @@ void AP_Generator_IE_2400::update_state_msg()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
|
// Get the MAV_SEVERITY level of a given error code
|
||||||
|
MAV_SEVERITY AP_Generator_IE_2400::get_mav_severity(uint32_t err_code) const
|
||||||
|
{
|
||||||
|
if (err_code <= 9) {
|
||||||
|
return MAV_SEVERITY_INFO;
|
||||||
|
}
|
||||||
|
if (err_code <= 20) {
|
||||||
|
return MAV_SEVERITY_WARNING;
|
||||||
|
}
|
||||||
|
return MAV_SEVERITY_CRITICAL;
|
||||||
|
}
|
||||||
|
#endif // HAL_GCS_ENABLED
|
||||||
|
|
||||||
#endif // AP_GENERATOR_IE_2400_ENABLED
|
#endif // AP_GENERATOR_IE_2400_ENABLED
|
||||||
|
|
|
@ -39,6 +39,11 @@ private:
|
||||||
// Check if we have received an warning code and populate message with warning code
|
// Check if we have received an warning code and populate message with warning code
|
||||||
bool check_for_warning_code(char* msg_txt, uint8_t msg_len) const override;
|
bool check_for_warning_code(char* msg_txt, uint8_t msg_len) const override;
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
|
// Get the MAV_SEVERITY level of a given error code
|
||||||
|
MAV_SEVERITY get_mav_severity(uint32_t err_code) const override;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Check for error codes that are deemed critical
|
// Check for error codes that are deemed critical
|
||||||
bool is_critical_error(const uint32_t err_in) const;
|
bool is_critical_error(const uint32_t err_in) const;
|
||||||
|
|
||||||
|
|
|
@ -179,14 +179,16 @@ void AP_Generator_IE_FuelCell::check_for_err_code_if_changed()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
char msg_txt[64];
|
char msg_txt[64];
|
||||||
if (check_for_err_code(msg_txt, sizeof(msg_txt)) || check_for_warning_code(msg_txt, sizeof(msg_txt))) {
|
if (check_for_err_code(msg_txt, sizeof(msg_txt)) || check_for_warning_code(msg_txt, sizeof(msg_txt))) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "%s", msg_txt);
|
GCS_SEND_TEXT(get_mav_severity(_err_code), "%s", msg_txt);
|
||||||
|
|
||||||
} else if ((_err_code == 0) && (_sub_err_code == 0)) {
|
} else if ((_err_code == 0) && (_sub_err_code == 0)) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Fuel cell error cleared");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Fuel cell error cleared");
|
||||||
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
_last_err_code = _err_code;
|
_last_err_code = _err_code;
|
||||||
_last_sub_err_code = _sub_err_code;
|
_last_sub_err_code = _sub_err_code;
|
||||||
|
|
|
@ -5,6 +5,7 @@
|
||||||
#if AP_GENERATOR_IE_ENABLED
|
#if AP_GENERATOR_IE_ENABLED
|
||||||
|
|
||||||
#include <AP_Logger/AP_Logger_config.h>
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
class AP_Generator_IE_FuelCell : public AP_Generator_Backend
|
class AP_Generator_IE_FuelCell : public AP_Generator_Backend
|
||||||
{
|
{
|
||||||
|
@ -117,5 +118,10 @@ protected:
|
||||||
// Print msg to user updating on state change
|
// Print msg to user updating on state change
|
||||||
virtual void update_state_msg();
|
virtual void update_state_msg();
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
|
// Get the MAV_SEVERITY level of a given error code
|
||||||
|
virtual MAV_SEVERITY get_mav_severity(uint32_t err_code) const { return MAV_SEVERITY_ALERT; }
|
||||||
|
#endif
|
||||||
|
|
||||||
};
|
};
|
||||||
#endif // AP_GENERATOR_IE_ENABLED
|
#endif // AP_GENERATOR_IE_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue