mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
APM: keep the time of the last heartbeat message
this will be used for failsafe processing
This commit is contained in:
parent
0584017aff
commit
8cb55eb75a
@ -368,6 +368,10 @@ static bool ch3_failsafe;
|
||||
static byte crash_timer;
|
||||
// A timer used to track how long since we have received the last GCS heartbeat or rc override message
|
||||
static uint32_t rc_override_fs_timer = 0;
|
||||
|
||||
// the time when the last HEARTBEAT message arrived from a GCS
|
||||
static uint32_t last_heartbeat_ms;
|
||||
|
||||
// A timer used to track how long we have been in a "short failsafe" condition due to loss of RC signal
|
||||
static uint32_t ch3_failsafe_timer = 0;
|
||||
|
||||
|
@ -1657,7 +1657,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||
if(msg->sysid != g.sysid_my_gcs) break;
|
||||
rc_override_fs_timer = millis();
|
||||
last_heartbeat_ms = rc_override_fs_timer = millis();
|
||||
pmTest1++;
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user