mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: rc_override active only on non-zero overrides
Bug found by Kevin Hester
This commit is contained in:
parent
7f97f7d0a3
commit
7935bf70f1
@ -1091,11 +1091,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
v[5] = packet.chan6_raw;
|
||||
v[6] = packet.chan7_raw;
|
||||
v[7] = packet.chan8_raw;
|
||||
hal.rcin->set_overrides(v, 8);
|
||||
|
||||
// record that rc are overwritten so we can trigger a failsafe if we lose contact with groundstation
|
||||
copter.failsafe.rc_override_active = true;
|
||||
// a RC override message is consiered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||
copter.failsafe.rc_override_active = hal.rcin->set_overrides(v, 8);
|
||||
|
||||
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||
copter.failsafe.last_heartbeat_ms = hal.scheduler->millis();
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user