mirror of https://github.com/ArduPilot/ardupilot
Rover: last_heartbeat_ms moved to failsafe structure
This commit is contained in:
parent
ed8feda5b9
commit
047f704236
|
@ -197,7 +197,7 @@ void Rover::ahrs_update()
|
|||
void Rover::gcs_failsafe_check(void)
|
||||
{
|
||||
if (g.fs_gcs_enabled) {
|
||||
failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000);
|
||||
failsafe_trigger(FAILSAFE_EVENT_GCS, failsafe.last_heartbeat_ms != 0 && (millis() - failsafe.last_heartbeat_ms) > 2000);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -813,7 +813,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
}
|
||||
|
||||
rover.last_heartbeat_ms = AP_HAL::millis();
|
||||
rover.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
||||
rover.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -265,6 +265,7 @@ private:
|
|||
uint32_t start_time;
|
||||
uint8_t triggered;
|
||||
uint32_t last_valid_rc_ms;
|
||||
uint32_t last_heartbeat_ms;
|
||||
} failsafe;
|
||||
|
||||
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
||||
|
@ -273,9 +274,6 @@ private:
|
|||
// true if we have a position estimate from AHRS
|
||||
bool have_position;
|
||||
|
||||
// the time when the last HEARTBEAT message arrived from a GCS
|
||||
uint32_t last_heartbeat_ms;
|
||||
|
||||
// obstacle detection information
|
||||
struct {
|
||||
// have we detected an obstacle?
|
||||
|
|
|
@ -138,6 +138,6 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action)
|
|||
void Rover::afs_fs_check(void)
|
||||
{
|
||||
// perform AFS failsafe checks
|
||||
g2.afs.check(rover.last_heartbeat_ms, rover.g2.fence.get_breaches() != 0, failsafe.last_valid_rc_ms);
|
||||
g2.afs.check(failsafe.last_heartbeat_ms, g2.fence.get_breaches() != 0, failsafe.last_valid_rc_ms);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue