diff --git a/libraries/APM_OBC/APM_OBC.cpp b/libraries/APM_OBC/APM_OBC.cpp index 529527c6e0..046e342497 100644 --- a/libraries/APM_OBC/APM_OBC.cpp +++ b/libraries/APM_OBC/APM_OBC.cpp @@ -74,6 +74,10 @@ APM_OBC::check(APM_OBC::control_mode mode, // mode. This tells it to pass through controls from the // receiver if (_manual_pin != -1) { + if (_manual_pin != _last_manual_pin) { + pinMode(_manual_pin, OUTPUT); + _last_manual_pin = _manual_pin; + } digitalWrite(_manual_pin, mode==OBC_MANUAL); } @@ -146,6 +150,10 @@ APM_OBC::check(APM_OBC::control_mode mode, // if we are not terminating then toggle the heartbeat pin at 10Hz if (!_terminate && _heartbeat_pin != -1) { + if (_heartbeat_pin != _last_heartbeat_pin) { + pinMode(_heartbeat_pin, OUTPUT); + _last_heartbeat_pin = _heartbeat_pin; + } _heartbeat_pin_value = !_heartbeat_pin_value; digitalWrite(_heartbeat_pin, _heartbeat_pin_value); } diff --git a/libraries/APM_OBC/APM_OBC.h b/libraries/APM_OBC/APM_OBC.h index df9df1d8f5..8d72dc3ae7 100644 --- a/libraries/APM_OBC/APM_OBC.h +++ b/libraries/APM_OBC/APM_OBC.h @@ -34,12 +34,8 @@ public: // Constructor APM_OBC(void) { - if (_heartbeat_pin != -1) { - pinMode(_heartbeat_pin, OUTPUT); - } - if (_manual_pin != -1) { - pinMode(_manual_pin, OUTPUT); - } + _last_heartbeat_pin = -1; + _last_manual_pin = -1; _state = STATE_PREFLIGHT; _terminate.set(0); @@ -64,6 +60,10 @@ private: AP_Int8 _manual_pin; AP_Int8 _terminate; + // last pins to cope with changing at runtime + int8_t _last_heartbeat_pin; + int8_t _last_manual_pin; + // waypoint numbers to jump to on failsafe conditions AP_Int8 _wp_comms_hold; AP_Int8 _wp_gps_loss;