Skip to content

Commit bf5442b

Browse files
Grigorii Fadeevclaude
andcommitted
Add DShot protocol reference documentation
- Add resources/dshot_protocol.md with full protocol specification: - Packet structure, timing, CRC calculation - Throttle range and special commands (0-47) - Bidirectional DShot and eRPM telemetry - Extended DShot Telemetry (EDT) - GCR encoding details - Hardware compatibility notes - Project-specific goals for motor lag analysis - Update CLAUDE.md: - Reference dshot_protocol.md from motor control section - Add motor pin assignments (Pin 4, 5) - Add display button pins (12-15) - Add future milestones: bidirectional DShot, motor response lag Sources: - https://brushlesswhoop.com/dshot-and-bidirectional-dshot/ - https://www.betaflight.com/docs/development/API/Dshot Co-Authored-By: Claude Opus 4.5 <noreply@anthropic.com>
1 parent 98d3d1f commit bf5442b

2 files changed

Lines changed: 178 additions & 0 deletions

File tree

CLAUDE.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@ Test bench for learning flight control systems, built around a Raspberry Pi Pico
2020
- Telemetry logging from both sensors (encoder + IMU)
2121
- Log lag and angle difference over time for troubleshooting and debugging
2222
- Implement control loops with lag compensation
23+
- Implement bidirectional DShot for ESC telemetry (RPM, voltage, temperature)
24+
- Analyze motor response lag (time between throttle command and RPM reaching target)
2325

2426
## Hardware Components
2527

@@ -60,6 +62,7 @@ Test bench for learning flight control systems, built around a Raspberry Pi Pico
6062
### Motor Control (`dshot/`)
6163

6264
- `dshot/jrddupont/dshot_pio.py` - DShot protocol via RP2040 PIO. Supports DSHOT150/300/600/1200.
65+
- See `resources/dshot_protocol.md` for full protocol specification (packet structure, timing, special commands, bidirectional DShot, telemetry).
6366

6467
### Examples (`examples/`)
6568

@@ -79,3 +82,6 @@ Small standalone scripts for testing individual sensors, calibration routines, a
7982

8083
- BNO085 reset: Pin 2
8184
- BNO085 interrupt: Pin 3
85+
- Motor 1 (DShot): Pin 4
86+
- Motor 2 (DShot): Pin 5
87+
- Display buttons: Pins 12 (A), 13 (B), 14 (X), 15 (Y)

resources/dshot_protocol.md

Lines changed: 172 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,172 @@
1+
# DShot Protocol Reference
2+
3+
Sources:
4+
- https://brushlesswhoop.com/dshot-and-bidirectional-dshot/
5+
- https://www.betaflight.com/docs/development/API/Dshot
6+
7+
## Packet Structure
8+
9+
DShot frames are **16 bits** organized as:
10+
```
11+
SSSSSSSSSSSTCCCC
12+
```
13+
- **S** (11 bits): Throttle value (0-2047)
14+
- **T** (1 bit): Telemetry request flag
15+
- **C** (4 bits): CRC checksum
16+
17+
## Throttle Range
18+
19+
| Value | Purpose |
20+
|-------|---------|
21+
| 0 | Disarmed / Motor stop |
22+
| 1-47 | Special commands |
23+
| 48-2047 | Throttle (2000 steps) |
24+
25+
## Timing Specifications
26+
27+
| Version | Bitrate | T1H (high=1) | T0H (high=0) | Bit Period | Frame Duration |
28+
|---------|---------|--------------|--------------|------------|----------------|
29+
| DSHOT150 | 150 kbit/s | 5.00 µs | 2.50 µs | 6.67 µs | 106.72 µs |
30+
| DSHOT300 | 300 kbit/s | 2.50 µs | 1.25 µs | 3.33 µs | 53.28 µs |
31+
| DSHOT600 | 600 kbit/s | 1.25 µs | 0.625 µs | 1.67 µs | 26.72 µs |
32+
| DSHOT1200 | 1200 kbit/s | 0.625 µs | 0.313 µs | 0.83 µs | 13.28 µs |
33+
34+
**Note:** Bits are distinguished by high-time duration within a fixed bit period.
35+
36+
## CRC Calculation
37+
38+
**Standard DShot:**
39+
```python
40+
crc = (value ^ (value >> 4) ^ (value >> 8)) & 0x0F
41+
```
42+
43+
**Bidirectional DShot (inverted):**
44+
```python
45+
crc = (~(value ^ (value >> 4) ^ (value >> 8))) & 0x0F
46+
```
47+
48+
## Arming Sequence
49+
50+
ESCs require sending throttle=0 for ~300ms before accepting throttle commands. This is the "arming" phase.
51+
52+
## Special Commands (0-47)
53+
54+
Commands only execute when motors are stopped.
55+
56+
| Command | Name | Notes |
57+
|---------|------|-------|
58+
| 0 | MOTOR_STOP | Reserved |
59+
| 1-5 | BEEP1-5 | Wait 260ms between commands |
60+
| 6 | ESC_INFO | Wait 12ms minimum |
61+
| 7 | SPIN_DIRECTION_1 | Requires 6 transmissions |
62+
| 8 | SPIN_DIRECTION_2 | Requires 6 transmissions |
63+
| 9 | 3D_MODE_OFF | Requires 6 transmissions |
64+
| 10 | 3D_MODE_ON | Requires 6 transmissions |
65+
| 12 | SAVE_SETTINGS | Requires 6x, wait 35ms |
66+
| 13 | EDT_ENABLE | EDT firmware only, requires 6x |
67+
| 14 | EDT_DISABLE | EDT firmware only, requires 6x |
68+
| 20 | SPIN_DIRECTION_NORMAL | Requires 6 transmissions |
69+
| 21 | SPIN_DIRECTION_REVERSED | Requires 6 transmissions |
70+
| 22-29 | LED control | On/off for LEDs 0-3 |
71+
| 32-35 | Signal-line telemetry | Enable/disable eRPM reporting |
72+
| 42 | Request temperature | |
73+
| 43 | Request voltage | |
74+
| 44 | Request current | |
75+
| 45 | Request consumption | |
76+
| 46 | Request eRPM | |
77+
| 47 | Request eRPM period | |
78+
79+
## Bidirectional DShot
80+
81+
Two-way communication on single wire. Only works with DSHOT300+.
82+
83+
**Key differences:**
84+
- Signal inverted: 1=low, 0=high
85+
- CRC inverted (see above)
86+
- ~30µs switching delay between TX and RX
87+
- Effective frame rate roughly halves
88+
89+
### eRPM Response Frame (16 bits)
90+
91+
```
92+
eeemmmmmmmmmcccc
93+
```
94+
- **e** (3 bits): Exponent (left-shift count)
95+
- **m** (9 bits): Period base value
96+
- **c** (4 bits): CRC (uninverted)
97+
98+
### GCR Encoding
99+
100+
eRPM values use Group Code Recording:
101+
1. 16-bit value → 20-bit GCR via nibble mapping
102+
2. Run-length encoding applied
103+
3. Transmitted at 5/4× base DShot bitrate
104+
105+
Decoding: `gcr = (value ^ (value >> 1))`
106+
107+
## Extended DShot Telemetry (EDT)
108+
109+
Additional telemetry within eRPM frames (no extra wiring).
110+
111+
Frames starting with `0mmmmmmmm` (second bit = 0) indicate EDT:
112+
113+
| Type | Data |
114+
|------|------|
115+
| 0x02 | Temperature (°C) |
116+
| 0x04 | Voltage (0.25V/step) |
117+
| 0x06 | Current (amperes) |
118+
| 0x08-0x0E | Debug values |
119+
120+
Requires firmware support on both ESC and flight controller.
121+
122+
## Hardware Compatibility
123+
124+
- **BLHeli_S**: DSHOT150/300 on EFM8BB1; all versions on newer MCUs
125+
- **BLHeli_32**: All DSHOT versions
126+
- **KISS ESCs**: All DSHOT versions
127+
- **Bluejay firmware**: DSHOT only (no analog)
128+
- **AM32 firmware**: Supports EDT
129+
130+
ESCs auto-detect protocol - no configuration needed.
131+
132+
## Frame Rate
133+
134+
Maximum theoretical: `1,000,000 / frame_duration`
135+
136+
| Version | Max Frames/sec |
137+
|---------|----------------|
138+
| DSHOT150 | ~9,370 |
139+
| DSHOT300 | ~18,768 |
140+
| DSHOT600 | ~37,425 |
141+
| DSHOT1200 | ~74,850 |
142+
143+
For 32kHz PID loops, DSHOT600+ required to avoid bottleneck.
144+
145+
## Implementation Notes for Pico
146+
147+
Current implementation (`dshot/jrddupont/dshot_pio.py`) uses PIO with 8 cycles per bit:
148+
- Cycles 0-1: Output low, read next bit
149+
- Cycles 2-4: Output high (always)
150+
- Cycles 5-7: Output high (if 1) or low (if 0)
151+
152+
PIO frequency = bitrate × 8 cycles/bit:
153+
- DSHOT150: 1.2 MHz
154+
- DSHOT300: 2.4 MHz
155+
- DSHOT600: 4.8 MHz
156+
- DSHOT1200: 9.6 MHz
157+
158+
## Project-Specific Goals
159+
160+
**Bidirectional DShot for this test bench:**
161+
162+
The test bench has multiple lag sources that affect control system performance:
163+
1. **IMU lag** - delay between physical movement and sensor reading (measured via AS5600 reference)
164+
2. **Motor response lag** - delay between throttle command and motor reaching target RPM
165+
166+
Implementing bidirectional DShot would enable:
167+
- Real-time RPM feedback from ESCs
168+
- Measuring motor response time (throttle → actual RPM)
169+
- ESC health monitoring (temperature, voltage)
170+
- Correlating commanded thrust with actual motor state
171+
172+
This data combined with IMU lag characterization will inform control loop design - the controller must predict not just where the lever *will be* (IMU lag) but also account for how long motors take to deliver requested thrust (motor lag).

0 commit comments

Comments
 (0)