Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Shorten dshot pulse width #20379

Merged
merged 2 commits into from
Mar 30, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 7 additions & 7 deletions libraries/AP_HAL/tests/test_prescaler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,36 +11,36 @@ class PrescalerParameterizedTestFixture :public ::testing::TestWithParam<uint32_
const uint32_t prescaler = AP_HAL::RCOutput::calculate_bitrate_prescaler(clock, target_rate, is_dshot);
// we would like at most a 1% discrepancy in target versus actual
const float rate_delta = fabsf(float(clock / prescaler) - target_rate) / target_rate;
EXPECT_TRUE(rate_delta < 0.20f);
EXPECT_TRUE(rate_delta < 0.13f);
}
};

TEST_P(PrescalerParameterizedTestFixture, DShot150) {
test_prescaler(GetParam(), 150000 * 20, true);
test_prescaler(GetParam(), 150000 * 8, true);
}

TEST_P(PrescalerParameterizedTestFixture, DShot300) {
test_prescaler(GetParam(), 300000 * 20, true);
test_prescaler(GetParam(), 300000 * 8, true);
}

TEST_P(PrescalerParameterizedTestFixture, DShot600) {
test_prescaler(GetParam(), 600000 * 20, true);
test_prescaler(GetParam(), 600000 * 8, true);
}

TEST_P(PrescalerParameterizedTestFixture, DShot1200) {
test_prescaler(GetParam(), 1200000 * 20, true);
test_prescaler(GetParam(), 1200000 * 8, true);
}

TEST_P(PrescalerParameterizedTestFixture, Passthrough) {
test_prescaler(GetParam(), 19200 * 10, false);
}

TEST_P(PrescalerParameterizedTestFixture, NeoPixel) {
test_prescaler(GetParam(), 800000 * 20, false);
test_prescaler(GetParam(), 800000 * 11, false);
}

TEST_P(PrescalerParameterizedTestFixture, ProfiLED) {
test_prescaler(GetParam(), 1500000 * 20, false);
test_prescaler(GetParam(), 1500000 * 11, false);
}

INSTANTIATE_TEST_CASE_P(
Expand Down
41 changes: 29 additions & 12 deletions libraries/AP_HAL_ChibiOS/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,18 @@ static const eventmask_t EVT_PWM_SYNTHETIC_SEND = EVENT_MASK(13);
static const eventmask_t EVT_PWM_SEND_NEXT = EVENT_MASK(14);
static const eventmask_t EVT_LED_SEND = EVENT_MASK(15);

static const uint32_t DSHOT_BIT_WIDTH_TICKS = 8;
static const uint32_t DSHOT_BIT_0_TICKS = 3;
static const uint32_t DSHOT_BIT_1_TICKS = 6;

// See WS2812B spec for expected pulse widths
static const uint32_t NEOP_BIT_WIDTH_TICKS = 11;
static const uint32_t NEOP_BIT_0_TICKS = 4;
static const uint32_t NEOP_BIT_1_TICKS = 9;
// neopixel does not use pulse widths at all
static const uint32_t PROFI_BIT_0_TICKS = 4;
static const uint32_t PROFI_BIT_1_TICKS = 9;

// #pragma GCC optimize("Og")

/*
Expand Down Expand Up @@ -882,7 +894,6 @@ void RCOutput::set_group_mode(pwm_group &group)
}

const uint32_t rate = protocol_bitrate(group.current_mode);
const uint32_t bit_period = 20;

// configure timer driver for DMAR at requested rate
const uint8_t pad_end_bits = 8;
Expand All @@ -893,7 +904,7 @@ void RCOutput::set_group_mode(pwm_group &group)
// calculate min time between pulses taking into account the DMAR parallelism
const uint32_t pulse_time_us = 1000000UL * bit_length / rate;

if (!setup_group_DMA(group, rate, bit_period, active_high, buffer_length, pulse_time_us, false)) {
if (!setup_group_DMA(group, rate, NEOP_BIT_WIDTH_TICKS, active_high, buffer_length, pulse_time_us, false)) {
group.current_mode = MODE_PWM_NONE;
break;
}
Expand All @@ -902,13 +913,12 @@ void RCOutput::set_group_mode(pwm_group &group)

case MODE_PWM_DSHOT150 ... MODE_PWM_DSHOT1200: {
const uint32_t rate = protocol_bitrate(group.current_mode);
const uint32_t bit_period = 20;
bool active_high = is_bidir_dshot_enabled() ? false : true;
// calculate min time between pulses
const uint32_t pulse_send_time_us = 1000000UL * dshot_bit_length / rate;

// configure timer driver for DMAR at requested rate
if (!setup_group_DMA(group, rate, bit_period, active_high,
if (!setup_group_DMA(group, rate, DSHOT_BIT_WIDTH_TICKS, active_high,
MAX(DSHOT_BUFFER_LENGTH, GCR_TELEMETRY_BUFFER_LEN), pulse_send_time_us, true)) {
group.current_mode = MODE_PWM_NORMAL;
break;
Expand Down Expand Up @@ -1293,8 +1303,8 @@ uint16_t RCOutput::create_dshot_packet(const uint16_t value, bool telem_request,
*/
void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
{
const uint32_t DSHOT_MOTOR_BIT_0 = 7 * clockmul;
const uint32_t DSHOT_MOTOR_BIT_1 = 14 * clockmul;
const uint32_t DSHOT_MOTOR_BIT_0 = DSHOT_BIT_0_TICKS * clockmul;
const uint32_t DSHOT_MOTOR_BIT_1 = DSHOT_BIT_1_TICKS * clockmul;
uint16_t i = 0;
for (; i < dshot_pre; i++) {
buffer[i * stride] = 0;
Expand Down Expand Up @@ -2181,8 +2191,8 @@ void RCOutput::_set_neopixel_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led,
const uint8_t stride = 4;
uint32_t *buf = grp->dma_buffer + (led * neopixel_bit_length + pad_start_bits) * stride + idx;
uint32_t bits = (green<<16) | (red<<8) | blue;
const uint32_t BIT_0 = 7 * grp->bit_width_mul;
const uint32_t BIT_1 = 14 * grp->bit_width_mul;
const uint32_t BIT_0 = NEOP_BIT_0_TICKS * grp->bit_width_mul;
const uint32_t BIT_1 = NEOP_BIT_1_TICKS * grp->bit_width_mul;
for (uint16_t b=0; b < 24; b++) {
buf[b * stride] = (bits & 0x800000) ? BIT_1 : BIT_0;
bits <<= 1;
Expand All @@ -2200,7 +2210,7 @@ void RCOutput::_set_profiled_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led,
const uint8_t stride = 4;
uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx;
uint32_t bits = 0x1000000 | (blue<<16) | (red<<8) | green;
const uint32_t BIT_1 = 14 * grp->bit_width_mul;
const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul;
for (uint16_t b=0; b < bit_length; b++) {
buf[b * stride] = (bits & 0x1000000) ? 0 : BIT_1;
bits <<= 1;
Expand All @@ -2217,7 +2227,7 @@ void RCOutput::_set_profiled_blank_frame(pwm_group *grp, uint8_t idx, uint8_t le
const uint8_t bit_length = 25;
const uint8_t stride = 4;
uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx;
const uint32_t BIT_1 = 14 * grp->bit_width_mul;
const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul;
for (uint16_t b=0; b < bit_length; b++) {
buf[b * stride] = BIT_1;
}
Expand All @@ -2232,7 +2242,7 @@ void RCOutput::_set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led)
const uint8_t bit_length = 25;
const uint8_t stride = 4;
uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx;
const uint32_t BIT_1 = 7 * grp->bit_width_mul;
const uint32_t BIT_1 = PROFI_BIT_0_TICKS * grp->bit_width_mul;
for (uint16_t b=0; b < bit_length; b++) {
buf[b * stride] = BIT_1;
}
Expand Down Expand Up @@ -2370,7 +2380,14 @@ void RCOutput::timer_info(ExpandingString &str)
str.printf("TIMERV1\n");

for (auto &group : pwm_group_list) {
const uint32_t target_freq = &group == serial_group ? 19200 * 10 : protocol_bitrate(group.current_mode) * 20;
uint32_t target_freq;
if (&group == serial_group) {
target_freq = 19200 * 10;
} else if (is_dshot_protocol(group.current_mode)) {
target_freq = protocol_bitrate(group.current_mode) * DSHOT_BIT_WIDTH_TICKS;
} else {
target_freq = protocol_bitrate(group.current_mode) * NEOP_BIT_WIDTH_TICKS;
}
const uint32_t prescaler = calculate_bitrate_prescaler(group.pwm_drv->clock, target_freq, is_dshot_protocol(group.current_mode));
str.printf("TIM%-2u CLK=%4uMhz MODE=%5s FREQ=%8u TGT=%8u\n", group.timer_id, unsigned(group.pwm_drv->clock / 1000000),
get_output_mode_string(group.current_mode),
Expand Down