mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_ChibiOS: add BLHeli_S ESC type and use it to control bitwidths
This commit is contained in:
parent
35a37cb84b
commit
cabaef6173
@ -471,6 +471,28 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz)
|
||||
_dshot_period_us = 1000000UL / drate;
|
||||
}
|
||||
|
||||
#ifndef DISABLE_DSHOT
|
||||
/*
|
||||
Set/get the dshot esc_type
|
||||
*/
|
||||
void RCOutput::set_dshot_esc_type(DshotEscType dshot_esc_type)
|
||||
{
|
||||
_dshot_esc_type = dshot_esc_type;
|
||||
switch (_dshot_esc_type) {
|
||||
case DSHOT_ESC_BLHELI_S:
|
||||
DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_S;
|
||||
DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_S;
|
||||
DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_S;
|
||||
break;
|
||||
default:
|
||||
DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_DEFAULT;
|
||||
DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_DEFAULT;
|
||||
DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_DEFAULT;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
find pwm_group and index in group given a channel number
|
||||
*/
|
||||
|
@ -172,7 +172,7 @@ public:
|
||||
/*
|
||||
Set/get the dshot esc_type
|
||||
*/
|
||||
void set_dshot_esc_type(DshotEscType dshot_esc_type) override { _dshot_esc_type = dshot_esc_type; }
|
||||
void set_dshot_esc_type(DshotEscType dshot_esc_type) override;
|
||||
|
||||
DshotEscType get_dshot_esc_type() const override { return _dshot_esc_type; }
|
||||
#endif
|
||||
|
@ -146,6 +146,7 @@ void RCOutput::update_channel_masks() {
|
||||
for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {
|
||||
switch (_dshot_esc_type) {
|
||||
case DSHOT_ESC_BLHELI:
|
||||
case DSHOT_ESC_BLHELI_S:
|
||||
if (_reversible_mask & (1U<<i)) {
|
||||
send_dshot_command(DSHOT_3D_ON, i + chan_offset, 0, 10, true);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user