mirror of https://github.com/ArduPilot/ardupilot
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:
parent
782fbe1ec5
commit
956ff65a25
|
@ -1559,7 +1559,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
v[6] = packet.chan7_raw;
|
v[6] = packet.chan7_raw;
|
||||||
v[7] = packet.chan8_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
|
// a RC override message is consiered to be a 'heartbeat' from
|
||||||
// the ground station for failsafe purposes
|
// the ground station for failsafe purposes
|
||||||
|
|
Loading…
Reference in New Issue