diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp index 529f073ccd..5a3c629850 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp @@ -60,7 +60,7 @@ static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(bool external_clock, uint8_t channel_offset, - uint8_t oe_pin_number) : + int16_t oe_pin_number) : _i2c_sem(NULL), _enable_pin(NULL), _frequency(50), @@ -95,9 +95,11 @@ void LinuxRCOutput_PCA9685::init(void* machtnicht) set_freq(0, 50); /* Enable PCA9685 PWM */ - _enable_pin = hal.gpio->channel(_oe_pin_number); - _enable_pin->mode(HAL_GPIO_OUTPUT); - _enable_pin->write(0); + if (_oe_pin_number != -1) { + _enable_pin = hal.gpio->channel(_oe_pin_number); + _enable_pin->mode(HAL_GPIO_OUTPUT); + _enable_pin->write(0); + } } void LinuxRCOutput_PCA9685::reset_all_channels() diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.h b/libraries/AP_HAL_Linux/RCOutput_PCA9685.h index 5a431b7db0..0a4bf8eb72 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.h +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.h @@ -6,8 +6,9 @@ class Linux::LinuxRCOutput_PCA9685 : public AP_HAL::RCOutput { public: + LinuxRCOutput_PCA9685(bool external_clock, uint8_t channel_offset, - uint8_t oe_pin_number); + int16_t oe_pin_number); ~LinuxRCOutput_PCA9685(); void init(void* machtnichts); void reset_all_channels(); @@ -32,7 +33,7 @@ private: bool _external_clock; uint8_t _channel_offset; - uint8_t _oe_pin_number; + int16_t _oe_pin_number; }; #endif // __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__