mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_ChibiOS: move bitwidths to AP_HAL
This commit is contained in:
parent
89ea5dc12c
commit
df35cb6243
@ -63,18 +63,6 @@ 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")
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user