Fix off-by-one reading PWM output values. Minor robustness tweaks.

This commit is contained in:
px4dev 2012-11-04 16:44:06 -08:00
parent 487597b385
commit 06e17eae5d
1 changed files with 5 additions and 9 deletions

View File

@ -171,10 +171,8 @@ pwm_channel_init(unsigned channel)
int int
up_pwm_servo_set(unsigned channel, servo_position_t value) up_pwm_servo_set(unsigned channel, servo_position_t value)
{ {
if (channel >= PWM_SERVO_MAX_CHANNELS) { if (channel >= PWM_SERVO_MAX_CHANNELS)
lldbg("pwm_channel_set: bogus channel %u\n", channel);
return -1; return -1;
}
unsigned timer = pwm_channels[channel].timer_index; unsigned timer = pwm_channels[channel].timer_index;
@ -214,17 +212,15 @@ up_pwm_servo_set(unsigned channel, servo_position_t value)
servo_position_t servo_position_t
up_pwm_servo_get(unsigned channel) up_pwm_servo_get(unsigned channel)
{ {
if (channel >= PWM_SERVO_MAX_CHANNELS) { if (channel >= PWM_SERVO_MAX_CHANNELS)
lldbg("pwm_channel_get: bogus channel %u\n", channel);
return 0; return 0;
}
unsigned timer = pwm_channels[channel].timer_index; unsigned timer = pwm_channels[channel].timer_index;
servo_position_t value = 0; servo_position_t value = 0;
/* test timer for validity */ /* test timer for validity */
if ((pwm_timers[timer].base == 0) || if ((pwm_timers[timer].base == 0) ||
(pwm_channels[channel].gpio == 0)) (pwm_channels[channel].timer_channel == 0))
return 0; return 0;
/* configure the channel */ /* configure the channel */
@ -246,7 +242,7 @@ up_pwm_servo_get(unsigned channel)
break; break;
} }
return value; return value + 1;
} }
int int
@ -261,7 +257,7 @@ up_pwm_servo_init(uint32_t channel_mask)
/* now init channels */ /* now init channels */
for (unsigned i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) { for (unsigned i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
/* don't do init for disabled channels; this leaves the pin configs alone */ /* don't do init for disabled channels; this leaves the pin configs alone */
if (((1 << i) & channel_mask) && (pwm_channels[i].gpio != 0)) if (((1 << i) & channel_mask) && (pwm_channels[i].timer_channel != 0))
pwm_channel_init(i); pwm_channel_init(i);
} }