Plane: RC override input should be considered as valid RC input

this prevents us setting trim values under joystick control
This commit is contained in:
Andrew Tridgell 2014-04-29 07:47:01 +10:00
parent 782fbe1ec5
commit 956ff65a25
1 changed files with 3 additions and 1 deletions

View File

@ -1559,7 +1559,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
v[6] = packet.chan7_raw;
v[7] = packet.chan8_raw;
hal.rcin->set_overrides(v, 8);
if (hal.rcin->set_overrides(v, 8)) {
failsafe.last_valid_rc_ms = hal.scheduler->millis();
}
// a RC override message is consiered to be a 'heartbeat' from
// the ground station for failsafe purposes