mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
HAL_PX4: auto-scale brushed output with ESC output range
This commit is contained in:
parent
e25b7e13e6
commit
ce5ed66b45
@ -327,13 +327,17 @@ void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
}
|
||||
|
||||
if (_output_mode == MODE_PWM_BRUSHED16KHZ) {
|
||||
// map form 1000 to 2000 onto zero to 100% duty cycle
|
||||
if (period_us <= 1000) {
|
||||
// map from the PWM range to 0 t0 100% duty cycle. For 16kHz
|
||||
// this ends up being 0 to 500 pulse width in units of
|
||||
// 125usec.
|
||||
const uint32_t period_max = 1000000UL/(16000/8);
|
||||
if (period_us <= _esc_pwm_min) {
|
||||
period_us = 0;
|
||||
} else if (period_us >= 2000) {
|
||||
period_us = 500;
|
||||
} else if (period_us >= _esc_pwm_max) {
|
||||
period_us = period_max;
|
||||
} else {
|
||||
period_us = (period_us - 1000)/2;
|
||||
uint32_t pdiff = period_us - _esc_pwm_min;
|
||||
period_us = pdiff*period_max/(_esc_pwm_max - _esc_pwm_min);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user