mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: make NeoPixel high-low proportions match for 0 and 1
This commit is contained in:
parent
cb9b4021e3
commit
3efab7495d
|
@ -406,7 +406,7 @@ public:
|
|||
|
||||
// See WS2812B spec for expected pulse widths
|
||||
static constexpr uint32_t NEOP_BIT_WIDTH_TICKS = 8;
|
||||
static constexpr uint32_t NEOP_BIT_0_TICKS = 3;
|
||||
static constexpr uint32_t NEOP_BIT_0_TICKS = 2;
|
||||
static constexpr uint32_t NEOP_BIT_1_TICKS = 6;
|
||||
// neopixel does not use pulse widths at all
|
||||
static constexpr uint32_t PROFI_BIT_0_TICKS = 7;
|
||||
|
|
Loading…
Reference in New Issue