mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
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:
parent
de50217809
commit
32994a5b1e
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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…
Reference in New Issue
Block a user