mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: only control widest pulse for dshot and oneshot
This commit is contained in:
parent
2ae6030f0c
commit
60b0df0a25
@ -582,14 +582,15 @@ void RCOutput::push_local(void)
|
|||||||
period_us = group.dshot_pulse_time_us;
|
period_us = group.dshot_pulse_time_us;
|
||||||
}
|
}
|
||||||
#endif //#ifndef DISABLE_DSHOT
|
#endif //#ifndef DISABLE_DSHOT
|
||||||
if (period_us > widest_pulse) {
|
|
||||||
widest_pulse = period_us;
|
|
||||||
}
|
|
||||||
if (group.current_mode == MODE_PWM_ONESHOT ||
|
if (group.current_mode == MODE_PWM_ONESHOT ||
|
||||||
group.current_mode == MODE_PWM_ONESHOT125 ||
|
group.current_mode == MODE_PWM_ONESHOT125 ||
|
||||||
group.current_mode == MODE_NEOPIXEL ||
|
group.current_mode == MODE_NEOPIXEL ||
|
||||||
group.current_mode == MODE_PROFILED ||
|
group.current_mode == MODE_PROFILED ||
|
||||||
is_dshot_protocol(group.current_mode)) {
|
is_dshot_protocol(group.current_mode)) {
|
||||||
|
// only control widest pulse for oneshot and dshot
|
||||||
|
if (period_us > widest_pulse) {
|
||||||
|
widest_pulse = period_us;
|
||||||
|
}
|
||||||
const uint8_t i = &group - pwm_group_list;
|
const uint8_t i = &group - pwm_group_list;
|
||||||
need_trigger |= (1U<<i);
|
need_trigger |= (1U<<i);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user