Browse Source

px4io: allow 0 as a PWM signal

sbg
Julian Oes 9 years ago
parent
commit
482ce55d57
  1. 7
      src/drivers/px4io/px4io.cpp

7
src/drivers/px4io/px4io.cpp

@ -2656,7 +2656,12 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) @@ -2656,7 +2656,12 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
/* TODO: we could go lower for e.g. TurboPWM */
unsigned channel = cmd - PWM_SERVO_SET(0);
if ((channel >= _max_actuators) || (arg < PWM_LOWEST_MIN) || (arg > PWM_HIGHEST_MAX)) {
PX4_INFO("pwm is %d (%d, %d)", arg, PWM_LOWEST_MIN, PWM_HIGHEST_MAX);
/* PWM needs to be either 0 or in the valid range. */
if ((arg != 0) && ((channel >= _max_actuators) ||
(arg < PWM_LOWEST_MIN) ||
(arg > PWM_HIGHEST_MAX))) {
ret = -EINVAL;
} else {

Loading…
Cancel
Save