mirror of https://github.com/ArduPilot/ardupilot
APM_OBC: handle separate terminate pin correctly
This commit is contained in:
parent
13145e4c01
commit
cca04d195a
|
@ -166,8 +166,9 @@ APM_OBC::check(APM_OBC::control_mode mode,
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if we are not terminating then toggle the heartbeat pin at 10Hz
|
// if we are not terminating or if there is a separate terminate
|
||||||
if (!_terminate && _heartbeat_pin != -1) {
|
// pin configured then toggle the heartbeat pin at 10Hz
|
||||||
|
if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
|
||||||
if (_heartbeat_pin != _last_heartbeat_pin) {
|
if (_heartbeat_pin != _last_heartbeat_pin) {
|
||||||
pinMode(_heartbeat_pin, OUTPUT);
|
pinMode(_heartbeat_pin, OUTPUT);
|
||||||
_last_heartbeat_pin = _heartbeat_pin;
|
_last_heartbeat_pin = _heartbeat_pin;
|
||||||
|
|
Loading…
Reference in New Issue