Browse Source

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
mission-4.1.18
Max Basescu 10 years ago committed by Andrew Tridgell
parent
commit
32994a5b1e
  1. 4
      libraries/AP_HAL_AVR/RCOutput_APM1.cpp
  2. 4
      libraries/AP_HAL_AVR/RCOutput_APM2.cpp

4
libraries/AP_HAL_AVR/RCOutput_APM1.cpp

@ -148,8 +148,8 @@ void APM1RCOutput::disable_ch(uint8_t ch) { @@ -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;
}

4
libraries/AP_HAL_AVR/RCOutput_APM2.cpp

@ -140,8 +140,8 @@ void APM2RCOutput::disable_ch(uint8_t ch) { @@ -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;
}

Loading…
Cancel
Save