mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: gcs fs not triggered if rc-overrides arrive
also not triggered if manual-control messages arrive also minor restructure of gcs_failsafe_check (non-functional) also remove unnecessary failsafe_trigger call when heartbeats arrive
This commit is contained in:
parent
047f704236
commit
6167e6ac0b
@ -196,9 +196,13 @@ void Rover::ahrs_update()
|
|||||||
*/
|
*/
|
||||||
void Rover::gcs_failsafe_check(void)
|
void Rover::gcs_failsafe_check(void)
|
||||||
{
|
{
|
||||||
if (g.fs_gcs_enabled) {
|
if (!g.fs_gcs_enabled) {
|
||||||
failsafe_trigger(FAILSAFE_EVENT_GCS, failsafe.last_heartbeat_ms != 0 && (millis() - failsafe.last_heartbeat_ms) > 2000);
|
// gcs failsafe disabled
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check for updates from GCS within 2 seconds
|
||||||
|
failsafe_trigger(FAILSAFE_EVENT_GCS, failsafe.last_heartbeat_ms != 0 && (millis() - failsafe.last_heartbeat_ms) > 2000);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -780,6 +780,8 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
RC_Channels::set_override(6, packet.chan7_raw, tnow);
|
RC_Channels::set_override(6, packet.chan7_raw, tnow);
|
||||||
RC_Channels::set_override(7, packet.chan8_raw, tnow);
|
RC_Channels::set_override(7, packet.chan8_raw, tnow);
|
||||||
|
|
||||||
|
// an RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||||
|
rover.failsafe.last_heartbeat_ms = tnow;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -803,18 +805,18 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
RC_Channels::set_override(uint8_t(rover.rcmap.roll() - 1), roll, tnow);
|
RC_Channels::set_override(uint8_t(rover.rcmap.roll() - 1), roll, tnow);
|
||||||
RC_Channels::set_override(uint8_t(rover.rcmap.throttle() - 1), throttle, tnow);
|
RC_Channels::set_override(uint8_t(rover.rcmap.throttle() - 1), throttle, tnow);
|
||||||
|
|
||||||
|
// a manual control message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||||
|
rover.failsafe.last_heartbeat_ms = tnow;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||||
{
|
{
|
||||||
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
// we keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||||
if (msg->sysid != rover.g.sysid_my_gcs) {
|
if (msg->sysid != rover.g.sysid_my_gcs) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
rover.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
rover.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
||||||
rover.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user