mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
HAL_ChibiOS: fixed output string for non-DMA capable chan
this fixes a problem where the user requests DShot (which rquired DMA) on an output channel which cannot allocate a DMA channel. We end up sending normal PWM, so the string representation of the output modes should reflect that
This commit is contained in:
parent
7114402d27
commit
126c6e589b
@ -648,7 +648,7 @@ void RCOutput::set_group_mode(pwm_group &group)
|
||||
|
||||
// configure timer driver for DMAR at requested rate
|
||||
if (!setup_group_DMA(group, rate, bit_period, true, dshot_buffer_length, false)) {
|
||||
group.current_mode = MODE_PWM_NONE;
|
||||
group.current_mode = MODE_PWM_NORMAL;
|
||||
break;
|
||||
}
|
||||
|
||||
@ -690,22 +690,23 @@ void RCOutput::set_group_mode(pwm_group &group)
|
||||
/*
|
||||
setup output mode
|
||||
*/
|
||||
void RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
|
||||
void RCOutput::set_output_mode(uint16_t mask, const enum output_mode mode)
|
||||
{
|
||||
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||
pwm_group &group = pwm_group_list[i];
|
||||
enum output_mode thismode = mode;
|
||||
if (((group.ch_mask << chan_offset) & mask) == 0) {
|
||||
// this group is not affected
|
||||
continue;
|
||||
}
|
||||
if (mode_requires_dma(mode) && !group.have_up_dma) {
|
||||
mode = MODE_PWM_NONE;
|
||||
if (mode_requires_dma(thismode) && !group.have_up_dma) {
|
||||
thismode = MODE_PWM_NORMAL;
|
||||
}
|
||||
if (mode > MODE_PWM_NORMAL) {
|
||||
fast_channel_mask |= group.ch_mask;
|
||||
}
|
||||
if (group.current_mode != mode) {
|
||||
group.current_mode = mode;
|
||||
if (group.current_mode != thismode) {
|
||||
group.current_mode = thismode;
|
||||
set_group_mode(group);
|
||||
}
|
||||
}
|
||||
|
@ -48,7 +48,7 @@ public:
|
||||
max_pwm = _esc_pwm_max;
|
||||
return true;
|
||||
}
|
||||
void set_output_mode(uint16_t mask, enum output_mode mode) override;
|
||||
void set_output_mode(uint16_t mask, const enum output_mode mode) override;
|
||||
bool get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) const override;
|
||||
|
||||
float scale_esc_to_unity(uint16_t pwm) override {
|
||||
|
Loading…
Reference in New Issue
Block a user