diff --git a/libraries/AP_HAL_VRBRAIN/RCOutput.cpp b/libraries/AP_HAL_VRBRAIN/RCOutput.cpp index 4f572e9910..7c7d050f64 100644 --- a/libraries/AP_HAL_VRBRAIN/RCOutput.cpp +++ b/libraries/AP_HAL_VRBRAIN/RCOutput.cpp @@ -559,7 +559,7 @@ void VRBRAINRCOutput::_timer_tick(void) /* enable sbus output */ -bool VRBRAINRCOutput::enable_sbus_out(uint16_t rate_hz) +bool VRBRAINRCOutput::enable_px4io_sbus_out(uint16_t rate_hz) { int fd = open("/dev/px4io", 0); if (fd == -1) { diff --git a/libraries/AP_HAL_VRBRAIN/RCOutput.h b/libraries/AP_HAL_VRBRAIN/RCOutput.h index 648127f0d4..638d5ceef8 100644 --- a/libraries/AP_HAL_VRBRAIN/RCOutput.h +++ b/libraries/AP_HAL_VRBRAIN/RCOutput.h @@ -35,7 +35,7 @@ public: void set_output_mode(enum output_mode mode) override; void _timer_tick(void); - bool enable_sbus_out(uint16_t rate_hz) override; + bool enable_px4io_sbus_out(uint16_t rate_hz) override; private: int _pwm_fd;