HAL_PX4: send all channels to px4io

this allows for 16 channel SBUS out
This commit is contained in:
Andrew Tridgell 2016-03-13 10:03:56 +11:00
parent 4bf3ec0e91
commit 2a6e64e358

View File

@ -399,11 +399,10 @@ void PX4RCOutput::_timer_tick(void)
if (_need_update && _pwm_fd != -1) { if (_need_update && _pwm_fd != -1) {
_need_update = false; _need_update = false;
perf_begin(_perf_rcout); perf_begin(_perf_rcout);
if (_max_channel <= _servo_count) { // always send all outputs to first PWM device. This ensures that SBUS is properly updated in px4io
::write(_pwm_fd, _period, _max_channel*sizeof(_period[0])); ::write(_pwm_fd, _period, _max_channel*sizeof(_period[0]));
} else { if (_max_channel > _servo_count) {
// we're using both sets of outputs // maybe send updates to alt_fd
::write(_pwm_fd, _period, _servo_count*sizeof(_period[0]));
if (_alt_fd != -1 && _alt_servo_count > 0) { if (_alt_fd != -1 && _alt_servo_count > 0) {
uint8_t n = _max_channel - _servo_count; uint8_t n = _max_channel - _servo_count;
if (n > _alt_servo_count) { if (n > _alt_servo_count) {