mirror of https://github.com/ArduPilot/ardupilot
Sub: Warn for leak detection
This commit is contained in:
parent
a811cfe7fb
commit
b364d94c43
|
@ -460,6 +460,8 @@ void Sub::dataflash_periodic(void)
|
|||
// three_hz_loop - 3.3hz loop
|
||||
void Sub::three_hz_loop()
|
||||
{
|
||||
set_leak_status(water_detector.update());
|
||||
|
||||
// check if we've lost contact with the ground station
|
||||
failsafe_gcs_check();
|
||||
|
||||
|
|
|
@ -302,6 +302,8 @@ private:
|
|||
uint8_t gcs : 1; // 4 // A status flag for the ground station failsafe
|
||||
uint8_t ekf : 1; // 5 // true if ekf failsafe has occurred
|
||||
uint8_t terrain : 1; // 6 // true if the missing terrain data failsafe has occurred
|
||||
uint8_t leak : 1; // true if leak recently detected
|
||||
uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs
|
||||
|
||||
int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
|
||||
|
||||
|
@ -1050,6 +1052,8 @@ private:
|
|||
void dataflash_periodic(void);
|
||||
void accel_cal_update(void);
|
||||
|
||||
void set_leak_status(bool status);
|
||||
|
||||
public:
|
||||
void mavlink_delay_cb();
|
||||
void failsafe_check();
|
||||
|
|
|
@ -73,6 +73,17 @@ void Sub::failsafe_battery_event(void)
|
|||
|
||||
}
|
||||
|
||||
void Sub::set_leak_status(bool status) {
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
failsafe.leak = status;
|
||||
|
||||
if(failsafe.leak && tnow > failsafe.last_leak_warn_ms + 5000) {
|
||||
failsafe.last_leak_warn_ms = tnow;
|
||||
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Leak Detected");
|
||||
}
|
||||
}
|
||||
|
||||
// failsafe_gcs_check - check for ground station failsafe
|
||||
void Sub::failsafe_gcs_check()
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue