Sub:consider RC_CHANNELS_OVERRIDE for pilot_input_failsafe

This commit is contained in:
Ohad Nir 2022-12-01 10:40:57 +02:00 committed by Andrew Tridgell
parent 205329575a
commit 8d366c16fb
1 changed files with 13 additions and 0 deletions

View File

@ -546,6 +546,19 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
break;
}
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { // MAV ID: 70
if (msg.sysid != sub.g.sysid_my_gcs) {
break; // Only accept control from our gcs
}
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
// a RC override message is considered to be a 'heartbeat'
// from the ground station for failsafe purposes
handle_rc_channels_override(msg);
break;
}
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82
// decode packet