|
|
|
@ -41,29 +41,29 @@ void PX4RCOutput::init(void* unused)
@@ -41,29 +41,29 @@ void PX4RCOutput::init(void* unused)
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* if we have 8 servos, then we are attached to PX4IO. In that
|
|
|
|
|
* case, we want to open the PX4FMU driver for the 4 additional |
|
|
|
|
* channels |
|
|
|
|
*/ |
|
|
|
|
if (_servo_count <= 4) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
_alt_fd = open("/dev/px4fmu", O_RDWR); |
|
|
|
|
if (_alt_fd == -1) { |
|
|
|
|
hal.console->printf("RCOutput: failed to open /dev/px4fmu"); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void PX4RCOutput::_init_alt_channels(void)
|
|
|
|
|
{ |
|
|
|
|
if (_alt_fd == -1) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
if (ioctl(_alt_fd, PWM_SERVO_ARM, 0) != 0) { |
|
|
|
|
hal.console->printf("RCOutput: Unable to setup alt IO arming\n"); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
#ifdef PWM_SERVO_SET_ARM_OK |
|
|
|
|
if (ioctl(_alt_fd, PWM_SERVO_SET_ARM_OK, 0) != 0) { |
|
|
|
|
hal.console->printf("RCOutput: Unable to setup alt IO arming OK\n"); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
if (ioctl(_alt_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_alt_servo_count) != 0) { |
|
|
|
|
hal.console->printf("RCOutput: Unable to get servo count\n");
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -122,7 +122,7 @@ void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
@@ -122,7 +122,7 @@ void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
|
|
|
|
|
|
|
|
|
uint16_t PX4RCOutput::get_freq(uint8_t ch)
|
|
|
|
|
{ |
|
|
|
|
if (_rate_mask & (1<<ch)) { |
|
|
|
|
if (_rate_mask & (1U<<ch)) { |
|
|
|
|
return _freq_hz; |
|
|
|
|
} |
|
|
|
|
return 50; |
|
|
|
@ -130,12 +130,18 @@ uint16_t PX4RCOutput::get_freq(uint8_t ch)
@@ -130,12 +130,18 @@ uint16_t PX4RCOutput::get_freq(uint8_t ch)
|
|
|
|
|
|
|
|
|
|
void PX4RCOutput::enable_ch(uint8_t ch) |
|
|
|
|
{ |
|
|
|
|
// channels are always enabled ...
|
|
|
|
|
if (ch >= 8 && !(_enabled_channels & (1U<<ch))) { |
|
|
|
|
// this is the first enable of an auxillary channel - setup
|
|
|
|
|
// aux channels now. This delayed setup makes it possible to
|
|
|
|
|
// use BRD_PWM_COUNT to setup the number of PWM channels.
|
|
|
|
|
_init_alt_channels(); |
|
|
|
|
} |
|
|
|
|
_enabled_channels |= (1U<<ch); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4RCOutput::disable_ch(uint8_t ch) |
|
|
|
|
{ |
|
|
|
|
// channels are always enabled ...
|
|
|
|
|
_enabled_channels &= ~(1U<<ch); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us) |
|
|
|
@ -159,6 +165,10 @@ void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
@@ -159,6 +165,10 @@ void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
|
|
|
|
if (ch >= _servo_count + _alt_servo_count) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
if (!(_enabled_channels & (1U<<ch))) { |
|
|
|
|
// not enabled
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
if (ch >= _max_channel) { |
|
|
|
|
_max_channel = ch + 1; |
|
|
|
|
} |
|
|
|
|