AP_HAL_AVR: Changed constrain_period to use RC_OUTPUT bounds instead of RC_INPUT

Done in order to get full range of motion for servo output
This commit is contained in:
Max Basescu 2015-06-04 19:56:54 -04:00 committed by Andrew Tridgell
parent de50217809
commit 32994a5b1e
2 changed files with 4 additions and 4 deletions

View File

@ -148,8 +148,8 @@ void APM1RCOutput::disable_ch(uint8_t ch) {
/* constrain pwm to be between min and max pulsewidth. */
static inline uint16_t constrain_period(uint16_t p) {
if (p > RC_INPUT_MAX_PULSEWIDTH) return RC_INPUT_MAX_PULSEWIDTH;
if (p < RC_INPUT_MIN_PULSEWIDTH) return RC_INPUT_MIN_PULSEWIDTH;
if (p > RC_OUTPUT_MAX_PULSEWIDTH) return RC_OUTPUT_MAX_PULSEWIDTH;
if (p < RC_OUTPUT_MIN_PULSEWIDTH) return RC_OUTPUT_MIN_PULSEWIDTH;
return p;
}

View File

@ -140,8 +140,8 @@ void APM2RCOutput::disable_ch(uint8_t ch) {
/* constrain pwm to be between min and max pulsewidth. */
static inline uint16_t constrain_period(uint16_t p) {
if (p > RC_INPUT_MAX_PULSEWIDTH) return RC_INPUT_MAX_PULSEWIDTH;
if (p < RC_INPUT_MIN_PULSEWIDTH) return RC_INPUT_MIN_PULSEWIDTH;
if (p > RC_OUTPUT_MAX_PULSEWIDTH) return RC_OUTPUT_MAX_PULSEWIDTH;
if (p < RC_OUTPUT_MIN_PULSEWIDTH) return RC_OUTPUT_MIN_PULSEWIDTH;
return p;
}