Compare commits

...

70 Commits

Author SHA1 Message Date
Jacob Dahl a3bb0d5b0a fix kconfig, add _REG32 2026-02-10 19:29:00 -09:00
Jacob Dahl 85dfa8c8b6 claudes first try 2026-02-10 19:22:02 -09:00
Jacob Dahl 789bdbd346 dshot: replace MOT_POLE_COUNT with per-motor parameters DSHOT_MOT_POL 2026-02-10 17:19:32 -09:00
Jacob Dahl e5068e1f1d cleanup print_status, rename perf counters 2026-02-10 14:06:27 -09:00
Jacob Dahl f78ce5b227 clean up 2026-02-10 12:43:29 -09:00
Jacob Dahl 4cfda1feed Merge branch 'main' into dev/dshot_stuff2 2026-02-10 12:29:38 -09:00
Jacob Dahl ae5b191c42 bump mavlink 2026-02-10 12:26:42 -09:00
Julian Oes 7e2361a592 dshot: fix EDT request
This fixes the EDT request for me. Basically, we re-request if an ESC
has gone offline, e.g. power has been briefly disconnected.

Also, it adds a 1s grace period to let the ESC start. Without this, for
me I run into a startup case where my AM32 ESC goes back offline for 1s
if the request happens immediately.
2026-02-06 16:29:51 +13:00
Julian Oes 7b0984584f dshot: add EDT data to status 2026-02-06 16:23:42 +13:00
Julian Oes b9f6e35a43 dshot: just publish at 200 Hz
It's tricky to figure out when to publish especially if some outputs
that should be reporting stop reporting. I had some edge cases where it
would not publish due timers not fully configured, so I decided to just
publish at 200 Hz no matter what data was there to publish.
2026-02-06 16:21:07 +13:00
alexklimaj f6a0ed57a4 dshot: remove redundant static_assert for ESC_MAX channels 2026-02-04 11:05:20 -07:00
alexklimaj 408a77376f ARKV6X fix flash overflow 2026-02-04 11:04:22 -07:00
Hamish Willee b1b3a695e7 Update to UORB docs according to standard 2026-02-04 08:58:08 +11:00
Julian Oes 53a4a871ef dshot: enable up to 16 DShot channels
For some boards, we can have DShot on 12 to 14 timer channels, so we
need to support up to 16 to have them covered.
2026-02-03 05:32:28 +13:00
Julian Oes 81a8a88db7 msg/mavlink: report up to 12 motors
This makes it consistent with the 12 motor output functions.
2026-02-03 05:31:52 +13:00
Julian Oes 130ec776b2 boards: don't use the word capture 2026-02-02 17:35:36 +13:00
Jacob Dahl b05c772ee3 dshot: module.yaml: esc_type default 0 2026-01-27 21:26:55 -09:00
Jacob Dahl 4f70ed367e dshot: fix optarg list 2026-01-27 21:06:33 -09:00
Jacob Dahl a9f5e5d70f remove extra newlines 2026-01-27 20:58:13 -09:00
Jacob Dahl ac5fba4c28 imxrt: add up_bdshot_channel_capture_supported 2026-01-27 20:34:48 -09:00
Jacob Dahl 6f8ba007d1 dshot: fix bug preventing writing settings 2026-01-27 19:39:06 -09:00
Jacob Dahl 47bb1437e4 adjust debug message 2026-01-27 18:54:09 -09:00
Julian Oes b26b3ac29d boards: fixup timers and DMA for KakuteH7-Wing 2026-01-27 15:39:49 -09:00
Julian Oes 3ef8b10987 dshot: improve status output 2026-01-27 15:39:49 -09:00
Julian Oes 0c51b25391 dshot: support timer channels without DMA capture
Some timer channels such as timer 4 channel 4 don't support DMA, so we
can only use them to burst/update but not to capture.
2026-01-27 15:39:49 -09:00
Jacob Dahl d72542a48d replace eeprom struct with opaque buffer 2026-01-27 15:39:49 -09:00
Jacob Dahl 5cde03652a fix date 2026-01-27 15:39:49 -09:00
Jacob Dahl bbbac3bb16 remove debug mavlink code 2026-01-27 15:39:49 -09:00
Jacob Dahl c9a8f37fef remove TODO 2026-01-27 15:39:49 -09:00
Jacob Dahl 44f62fd764 rename perf counters, skip burst delay on last channel 2026-01-27 15:39:49 -09:00
Jacob Dahl 89f14100ab Update platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c
Co-authored-by: Julian Oes <julian@oes.ch>
2026-01-27 15:39:49 -09:00
Jacob Dahl b1585a7f55 Update platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c
Co-authored-by: Julian Oes <julian@oes.ch>
2026-01-27 15:39:49 -09:00
Julian Oes e835394d25 mavlink: fixup ifdefs around ESC_EEPROM 2026-01-27 15:39:49 -09:00
Jacob Dahl 4d09521d98 make format 2026-01-27 15:39:49 -09:00
Jacob Dahl 8847c3cc83 dshot: trigger timers at the same time, with 10us delay between bursts to work around race condition 2026-01-27 15:39:49 -09:00
Jacob Dahl 7edc606296 don't use DSHOT_TEL_CFG directly in code since it is autogenerated only if a board has serial config 2026-01-27 15:39:49 -09:00
Jacob Dahl 6bc0e0c74e dshot: imxrt: fix unsigned to uint8_t in dshot_motor_data_set 2026-01-27 15:39:49 -09:00
Jacob Dahl 9ad690dc85 fix rpm overflow, change type to int32 2026-01-27 15:39:49 -09:00
Jacob Dahl c434ef1507 fix build and rename _param_escs_checks_required 2026-01-27 15:39:49 -09:00
Jacob Dahl 458c775bfd fix ifdef, adjust esc isInRange check 2026-01-27 15:39:49 -09:00
Jacob Dahl 24d7cd48e5 board: ark_fpv: add rc.board_airframes to reduce flash 2026-01-27 15:39:49 -09:00
Jacob Dahl b5e9457ba2 remove bdshot_timing_analyzer_spec.md 2026-01-27 15:39:49 -09:00
Jacob Dahl 597611e7a5 code simplifier 2026-01-27 15:39:49 -09:00
Jacob Dahl 2d7b3a83c3 bdshot_analyzer.py for saleae timign analysis 2026-01-27 15:39:49 -09:00
Jacob Dahl 72cd09bd87 fix handling MAV_CMD_CONFIGURE_ACTUATOR -1000 2026-01-27 15:39:49 -09:00
Jacob Dahl 4ee3d2778e sequential dshot burst/capture timer triggering, it works! 2026-01-27 15:39:49 -09:00
Jacob Dahl bf783779b6 fix esc online mask ordering, fix bdshot channels ready check, improve dshot status formatting 2026-01-27 15:39:49 -09:00
Jacob Dahl 8ab112b4c3 after claudes fixes 2026-01-27 15:39:49 -09:00
Jacob Dahl 3c8a652538 before claude 2026-01-27 15:39:49 -09:00
Jacob Dahl f6eeacfd8b temporarily comment out dshot re-init 2026-01-27 15:39:49 -09:00
Jacob Dahl 22587b09e5 bdshot per channel, use PWM_TIM param for BDSHOT instead of single parameter to allow per timer bdshot, clean up logic and fix minor bugs, re-init dshot in mixerChanged 2026-01-27 15:39:49 -09:00
Jacob Dahl 4b3cd1e9a2 fix names and variables and remove dead code 2026-01-27 15:39:49 -09:00
Jacob Dahl d1d54178d9 fix issues found during review, clean up 2026-01-27 15:39:49 -09:00
Jacob Dahl 46cecf61c5 multi timer, first pass 2026-01-27 15:39:49 -09:00
Jacob Dahl 3b9ea305f7 clean up naming 2026-01-27 15:39:49 -09:00
Jacob Dahl c6c8cdd78f mavlink submodule 2026-01-27 15:39:49 -09:00
Jacob Dahl e6744590cf rename to ESC_EEPROM and fix up logic for 192 length 2026-01-27 15:39:49 -09:00
Jacob Dahl 22ac08547e update mavlink 2026-01-27 15:39:49 -09:00
Jacob Dahl b4e69e95fa update mavlink 2026-01-27 15:39:49 -09:00
Jacob Dahl 55cdb4d192 it's working 2026-01-27 15:39:49 -09:00
Jacob Dahl 5c7e33d2cb fixup mavlink, enable development on ARK FPV 2026-01-27 15:39:49 -09:00
Jacob Dahl bd4ac2a11b added mavlink submodule 2026-01-27 15:39:49 -09:00
Jacob Dahl 1d576c074b added am32_eeprom to mavlink 2026-01-27 15:39:49 -09:00
Jacob Dahl 9761cb3d6f improve dshot status output 2026-01-27 15:39:49 -09:00
Jacob Dahl bc89140345 cleaned up 2026-01-27 15:39:49 -09:00
Jacob Dahl 316c0c187a adaptive gcr bit width tracking 2026-01-27 15:39:49 -09:00
Jacob Dahl a63f1809ff increase telem processing delay from 3 to 5 seconds 2026-01-27 15:39:49 -09:00
Jacob Dahl 844b5adab2 add no_data counter 2026-01-27 15:39:49 -09:00
Jacob Dahl 74da73e37d fix frame quantization 2026-01-27 15:39:49 -09:00
Jacob Dahl b93cb96c4f rebased 2026-01-27 15:39:49 -09:00
44 changed files with 4776 additions and 1530 deletions
+467
View File
@@ -0,0 +1,467 @@
# Bitbang DShot Prototype - Design Specification
## Goal
Implement bitbang DShot (including bidirectional) as an alternative to the existing DMA burst/capture approach in the STM32H7 platform layer. The implementation is generic - it works on any STM32H7 board by dynamically discovering port/pin groupings from `timer_io_channels[]` at init time. The **ARK FPV** board is the test target.
Bitbang DShot uses a pacer timer to trigger DMA transfers to/from GPIO registers (BSRR for output, IDR for input), instead of using timer PWM channels with DMA burst to CCR registers. This decouples motor signal generation from timer channel hardware and enables simultaneous capture of all motors on a GPIO port (eliminating round-robin).
## Key Advantage Over Current Approach
The current BDShot implementation captures **one motor per timer per cycle** (round-robin) because each capture channel needs its own DMA stream. At 200Hz update rate, each motor gets RPM updates at only 50Hz (200/4).
Bitbang capture reads the entire GPIO IDR register on every sample, capturing **all motors on a port simultaneously**. Every cycle produces RPM data for every motor - a 4x improvement in per-motor RPM update rate.
## Architecture Overview
### Current (DMA Burst/Capture)
```
Timer (PWM mode) ──► CCR1-CCR4 (via DMA burst to DMAR) ──► Pin AF output
Timer (Capture mode) ──► CCR edge timestamps (via per-channel DMA) ──► one channel at a time
```
### Bitbang
```
Timer (counter mode) ──► Update event triggers DMA ──► writes BSRR words to GPIO port
Timer (counter mode) ──► Update event triggers DMA ──► reads IDR from GPIO port (all pins)
```
## Port Group Discovery
At init time, the implementation iterates `timer_io_channels[]` and groups channels by GPIO port. The port and pin are extracted from the existing `gpio_out` field using NuttX bit encoding:
```c
#include <stm32_gpio.h> // GPIO_PORT_MASK, GPIO_PORT_SHIFT, GPIO_PIN_MASK, GPIO_PIN_SHIFT
// Extract port index and pin number from timer_io_channels[ch].gpio_out
uint8_t port_index = (gpio_out & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; // 0=A, 1=B, ... 7=H, 8=I
uint8_t pin_number = (gpio_out & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT; // 0-15
// Get GPIO peripheral base address from NuttX lookup table
uint32_t gpio_base = g_gpiobase[port_index]; // e.g., STM32_GPIOH_BASE = 0x58021C00
```
### Port Group Init Algorithm
```c
// Pseudocode for up_dshot_init()
for (uint8_t ch = 0; ch < MAX_TIMER_IO_CHANNELS; ch++) {
if (!(channel_mask & (1 << ch))) continue;
uint32_t gpio_out = timer_io_channels[ch].gpio_out;
uint8_t port_index = (gpio_out & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin_num = (gpio_out & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
uint8_t timer_index = timer_io_channels[ch].timer_index;
// Find or create port group for this GPIO port
port_group_t *pg = find_or_create_port_group(port_index);
pg->gpio_base = g_gpiobase[port_index];
pg->pin_mask |= (1 << pin_num);
pg->moder_mask |= (3 << (pin_num * 2));
pg->moder_output |= (1 << (pin_num * 2)); // 01 = output mode
pg->pin_numbers[pg->pin_count] = pin_num;
pg->output_channels[pg->pin_count] = ch;
pg->pin_count++;
// Assign a pacer timer - use the first timer associated with any motor on this port.
// On H7 with DMAMUX the timer just needs a TIMx_UP DMA mapping; any timer works.
if (pg->timer_index == UINT8_MAX) {
pg->timer_index = timer_index;
}
}
```
This works on any board. Motors on the same GPIO port share a port group regardless of which timer they were originally assigned to.
### ARK FPV Example (test target)
On the ARK FPV, the above algorithm produces two port groups:
| Motor | GPIO | Pin | Port Group | Pacer Timer |
|---------|-------|-----|------------|-------------|
| FMU_CH1 | PI0 | 0 | Port I | TIM5 (first timer seen on Port I) |
| FMU_CH2 | PH12 | 12 | Port H | TIM5 |
| FMU_CH3 | PH11 | 11 | Port H | TIM5 |
| FMU_CH4 | PH10 | 10 | Port H | TIM5 |
| FMU_CH5 | PI5 | 5 | Port I | (already assigned) |
| FMU_CH6 | PI6 | 6 | Port I | (already assigned) |
| FMU_CH7 | PI7 | 7 | Port I | (already assigned) |
| FMU_CH8 | PI2 | 2 | Port I | (already assigned) |
- **Port H group**: 3 motors, pin_mask=0x1C00, pacer=TIM5
- **Port I group**: 5 motors, pin_mask=0xE5, pacer=TIM5 (first timer found; could also be TIM8)
Note: The pacer timer just needs a valid `dma_map_up` entry. The first timer encountered for a port group is used. Since DMAMUX on H7 can route any timer update event to any DMA stream, any timer with DMA configured works as a pacer.
## GPIO Registers (STM32H7)
```
Offset 0x00: MODER - Mode register (2 bits/pin: 00=input, 01=output, 10=AF, 11=analog)
Offset 0x10: IDR - Input data register (read-only, bits [15:0] = pin state)
Offset 0x14: ODR - Output data register
Offset 0x18: BSRR - Bit set/reset register (write-only, atomic)
Bits [15:0] = SET (writing 1 sets pin HIGH)
Bits [31:16] = RESET (writing 1 sets pin LOW)
Writing 0 = no change
```
GPIO base addresses are looked up at runtime via `g_gpiobase[port_index]` (NuttX global array).
### MODER Manipulation
Pin masks and MODER masks are computed dynamically during port group init from the discovered pin numbers:
```c
// For each pin in the port group:
pg->pin_mask |= (1 << pin_num); // for BSRR set/reset
pg->moder_mask |= (3 << (pin_num * 2)); // which MODER bits to touch
pg->moder_output |= (1 << (pin_num * 2)); // 01 = general purpose output
// moder_input is always 0 (clear the bits = input mode)
```
To switch to output: `modifyreg32(gpio_base + STM32_GPIO_MODER_OFFSET, pg->moder_mask, pg->moder_output)`
To switch to input: `modifyreg32(gpio_base + STM32_GPIO_MODER_OFFSET, pg->moder_mask, 0)`
## DMA Configuration
The DMA request source (DMAMUX) stays the same as current - TIMx_UP triggers each DMA transfer. The only change is the **peripheral address** and **transfer direction**.
### Output DMA (Memory → GPIO BSRR)
```c
// Peripheral address is GPIO BSRR instead of TIM DMAR
px4_stm32_dmasetup(pg->dma_handle,
pg->gpio_base + STM32_GPIO_BSRR_OFFSET, // e.g., 0x58021C18 for Port H
(uint32_t)bsrr_output_buffer[pg_index],
SUBPERIODS_PER_BIT * DSHOT_FRAME_BITS, // 20 * 16 = 320 transfers (+ 1 trailing zero)
DMA_SCR_PRIHI | DMA_SCR_MSIZE_32BITS | DMA_SCR_PSIZE_32BITS |
DMA_SCR_MINC | DMA_SCR_DIR_M2P | DMA_SCR_TCIE);
```
### Input DMA (GPIO IDR → Memory)
```c
px4_stm32_dmasetup(pg->dma_handle,
pg->gpio_base + STM32_GPIO_IDR_OFFSET, // e.g., 0x58021C10 for Port H
(uint32_t)idr_capture_buffer[pg_index],
CAPTURE_SAMPLE_COUNT, // enough samples for GCR frame (~512)
DMA_SCR_PRIHI | DMA_SCR_MSIZE_16BITS | DMA_SCR_PSIZE_16BITS |
DMA_SCR_MINC | DMA_SCR_DIR_P2M | DMA_SCR_TCIE);
```
### DMAMUX Routing (unchanged)
Each port group uses its pacer timer's `dma_map_up` for DMAMUX routing:
```c
pg->dma_handle = stm32_dmachannel(io_timers[pg->timer_index].dshot.dma_map_up);
```
The DMAMUX determines **when** the DMA fires (on timer update events). The DMA stream registers determine **what** gets transferred (BSRR/IDR addresses). These are independent - the DMA request source and transfer target don't need to be the same peripheral.
## Timer Configuration
Each port group's pacer timer is configured as a simple upcounter. No PWM output, no capture-compare - just generate periodic update events.
```c
// Same prescaler as current DShot implementation
rPSC(timer) = ((timer_clock_freq / dshot_pwm_freq) / DSHOT_MOTOR_PWM_BIT_WIDTH) - 1;
rARR(timer) = DSHOT_MOTOR_PWM_BIT_WIDTH - 1; // 19 (20 counts per sub-period)
// Enable update DMA request
rDIER(timer) |= ATIM_DIER_UDE;
// Enable counter
rCR1(timer) |= GTIM_CR1_CEN;
```
With `DSHOT_MOTOR_PWM_BIT_WIDTH = 20`, each timer update fires DMA once per sub-period. One DShot bit = 20 sub-periods.
## Output Buffer Layout (BSRR Words)
Each DShot frame is 16 bits. Each bit has 20 sub-periods. The buffer contains one 32-bit BSRR word per sub-period.
**DShot bit waveform (sub-periods 0-19):**
- Bit '1' (70% duty): SET at sub-period 0, RESET at sub-period 14, zeros elsewhere
- Bit '0' (35% duty): SET at sub-period 0, RESET at sub-period 7, zeros elsewhere
**Buffer structure per port:**
```
[bit0_subperiod0] [bit0_subperiod1] ... [bit0_subperiod19]
[bit1_subperiod0] [bit1_subperiod1] ... [bit1_subperiod19]
...
[bit15_subperiod0] [bit15_subperiod1] ... [bit15_subperiod19]
[trailing_zero] ← ensures all pins return LOW at frame end
```
Total: (16 * 20) + 1 = 321 BSRR words = 1284 bytes per port.
**Encoding example** (3 motors on pins 10, 11, 12 of some port, sending bits 1, 0, 1):
```
Sub-period 0: BSRR = (1<<10) | (1<<11) | (1<<12) = 0x00001C00 (SET all three)
Sub-period 7: BSRR = (1<<(11+16)) = 0x00080000 (RESET pin11 only - it's '0')
Sub-period 14: BSRR = (1<<(10+16)) | (1<<(12+16)) = 0x14000000 (RESET pin10, pin12 - they're '1')
All other sub-periods: BSRR = 0x00000000 (no change)
```
### Motor Data Set Function
The port group index and pin number for each output channel are determined at init time and stored in a lookup table. No per-frame discovery needed.
```c
// Populated during up_dshot_init() from timer_io_channels[ch].gpio_out
static uint8_t _channel_to_port_group[MAX_TIMER_IO_CHANNELS];
static uint8_t _channel_to_pin[MAX_TIMER_IO_CHANNELS];
void dshot_motor_data_set(uint8_t output_channel, uint16_t packet)
{
uint8_t pg_index = _channel_to_port_group[output_channel];
uint8_t pin_num = _channel_to_pin[output_channel];
uint32_t set_mask = (1 << pin_num);
uint32_t reset_mask = (1 << (pin_num + 16));
uint32_t *buffer = bsrr_output_buffer[pg_index];
for (int bit = 0; bit < 16; bit++) {
int base = bit * SUBPERIODS_PER_BIT;
bool is_one = (packet >> (15 - bit)) & 1; // MSB first
int reset_point = is_one ? MOTOR_PWM_BIT_1 : MOTOR_PWM_BIT_0;
buffer[base + 0] |= set_mask; // SET at start of bit
buffer[base + reset_point] |= reset_mask; // RESET at duty cycle end
}
}
```
Note: Buffer must be zeroed before building each frame, then all motors OR their masks into the shared per-port buffer.
## Capture Buffer Layout (IDR Samples)
After transmitting, GPIO pins switch to input mode. DMA samples the IDR register at the same timer rate (20 sub-periods per DShot bit period).
**GCR response timing:**
- GCR bit rate = DShot bit rate * 5/4 (750kHz for DShot600)
- GCR bit period = 1.333us
- Sample period = 83.3ns (at DShot600 with 20 sub-periods)
- Samples per GCR bit = ~16 (heavy oversampling, good for edge detection)
- GCR frame = 21 bits = ~336 samples minimum
- Use 400-512 samples to be safe
**Buffer:** Array of uint16_t, one per IDR sample.
```
[idr_sample_0] [idr_sample_1] ... [idr_sample_N]
```
Each sample contains all 16 pins of the port. Extract per-motor bitstream by masking:
```c
bool pin_state = (idr_sample >> pin_num) & 1;
```
### Capture Processing
Convert IDR samples to edge intervals, then reuse existing GCR decoder:
```c
void process_bitbang_capture(uint8_t port_group, uint8_t pin_num, uint8_t output_channel)
{
uint16_t *buffer = idr_capture_buffer[port_group];
uint32_t intervals[32];
unsigned interval_count = 0;
// Extract edges from IDR samples
bool prev_state = (buffer[0] >> pin_num) & 1;
unsigned last_edge = 0;
for (unsigned i = 1; i < CAPTURE_SAMPLE_COUNT; i++) {
bool state = (buffer[i] >> pin_num) & 1;
if (state != prev_state) {
// Edge detected
if (last_edge > 0 && interval_count < 32) {
intervals[interval_count++] = i - last_edge;
}
last_edge = i;
prev_state = state;
}
}
// Now decode using same GCR logic as existing code
// intervals[] contains sample counts between edges
// (equivalent to CCR timestamp differences in current impl)
}
```
The existing `convert_edge_intervals_to_bitstream()` logic (adaptive base interval, bit counting, RLL/GCR decode, CRC check) can be reused with minor adaptation since the interval units are now sample counts instead of timer ticks. The ratio math is identical.
## Sequence of Operations
### Per-cycle flow (called from `up_dshot_trigger()`):
```
1. TRANSMIT PHASE
a. Zero the BSRR output buffers for all port groups
b. Build BSRR buffers (call dshot_motor_data_set for each motor)
- Each motor ORs its pin masks into its port group's shared buffer
c. Configure GPIO pins as output (MODER = 01) for each port group
d. Flush dcache on output buffers
e. For each port group:
- Allocate DMA via stm32_dmachannel(io_timers[pg->timer_index].dshot.dma_map_up)
- Setup DMA: memory→BSRR, 32-bit, 321 transfers
- Enable timer UDE (update DMA request)
- Start DMA with burst_finished_callback
- Enable timer counter
f. ~27us later (16 bits × 20 sub-periods × 83.3ns), DMA complete fires
2. TRANSITION PHASE (in burst_finished_callback, per port group)
a. Stop DMA, free DMA handle
b. Disable timer
c. Switch GPIO pins to input mode (MODER = 00)
d. Schedule capture start via hrt_call_after(30us)
3. CAPTURE PHASE (in capture_start_callback, per port group)
a. Zero capture buffer for this port group
b. Flush dcache
c. Allocate DMA via stm32_dmachannel(dma_map_up) [reuse same DMAMUX route]
d. Setup DMA: IDR→memory, 16-bit, 512 transfers
e. Enable timer UDE, start DMA, enable timer
f. Schedule capture_complete via hrt_call_after(frame_time + margin)
4. PROCESSING PHASE (in capture_complete_callback, per port group)
a. Stop DMA, free DMA handle
b. Disable timer
c. Invalidate dcache on capture buffer
d. For EACH motor on the port (not round-robin!):
- Extract per-pin bitstream from IDR samples using pin_numbers[]
- Detect edges, compute intervals
- Decode GCR → eRPM/EDT
e. Switch GPIO back to output mode (MODER = 01)
f. Mark port group cycle complete
```
## File Structure
### New file: `platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot_bitbang.c`
Implements the same `up_dshot_*` API as `dshot.c`:
- `up_dshot_init()` - Initialize port groups, allocate DMA, configure timers
- `up_dshot_trigger()` - Start the TX→wait→RX→process cycle
- `dshot_motor_data_set()` - Build BSRR words into port group buffers
- `up_dshot_arm()` - Enable/disable GPIO output
- `up_bdshot_get_erpm()` - Return captured eRPM (unchanged)
- `up_bdshot_channel_online()` - Return online status (unchanged)
- `up_bdshot_status()` - Print diagnostics
### New/modified: `platforms/nuttx/src/px4/stm/stm32_common/dshot/CMakeLists.txt`
Add build option to select `dshot.c` vs `dshot_bitbang.c`.
### Board-level config
No board-specific changes needed. The bitbang implementation reads the same `io_timers[]` and `timer_io_channels[]` structures that every board already defines. It extracts GPIO port/pin from `timer_io_channels[].gpio_out` (which `initIOTimerChannel()` already populates with `getGPIOPort(pin.port) | getGPIOPin(pin.pin)`) and the DMA mapping from `io_timers[].dshot.dma_map_up`.
A board opts into bitbang mode via a build flag or Kconfig option that selects `dshot_bitbang.c` instead of `dshot.c`.
### What stays the same
- `drv_dshot.h` API - no changes
- `DShot.cpp` / `DShot.h` (the driver module) - no changes
- `DShotTelemetry.cpp` / `DShotTelemetry.h` - no changes
- GCR decoding logic - copied/adapted from dshot.c but the core algorithm is identical
- All higher-level consumers of eRPM data
## Data Structures
```c
#define MAX_PORT_GROUPS 4 // Max distinct GPIO ports with motor pins (typically 1-3)
#define MAX_PINS_PER_GROUP 8
// Port group: one per GPIO port that has motor pins. Built dynamically at init.
typedef struct port_group_t {
uint32_t gpio_base; // GPIO port base address (from g_gpiobase[])
uint8_t port_index; // NuttX port index (0=A, 7=H, 8=I, etc.)
uint32_t pin_mask; // Bitmask of motor pins on this port
uint32_t moder_mask; // MODER register mask for mode switching
uint32_t moder_output; // MODER value for output mode (01 per pin)
uint8_t pin_count; // Number of motor pins on this port
uint8_t pin_numbers[MAX_PINS_PER_GROUP]; // Pin numbers (0-15)
uint8_t output_channels[MAX_PINS_PER_GROUP]; // Corresponding output channel indices
uint8_t timer_index; // Pacer timer index (into io_timers[])
DMA_HANDLE dma_handle; // DMA stream handle (reused between TX/RX)
bool bidirectional; // BDShot enabled for this group
bool cycle_complete; // Ready for next trigger
} port_group_t;
static port_group_t _port_groups[MAX_PORT_GROUPS] = {};
static uint8_t _num_port_groups = 0;
// Per-channel lookup tables (populated at init from timer_io_channels[].gpio_out)
static uint8_t _channel_to_port_group[MAX_TIMER_IO_CHANNELS];
static uint8_t _channel_to_pin[MAX_TIMER_IO_CHANNELS];
```
## DMA Resource Usage Comparison
### Current (DMA burst + capture)
- **Output**: 1 DMA stream per timer = N_timers streams
- **Capture**: 1 DMA stream per captured channel (round-robin, 1 at a time per timer)
- DMA streams are freed/reallocated between burst and capture phases
### Bitbang
- **Output**: 1 DMA stream per port group = N_ports streams
- **Capture**: 1 DMA stream per port group (same streams, reconfigured)
- DMA streams freed/reallocated between phases (same pattern as current)
DMA resource usage is equivalent (typically N_timers == N_ports or close). The DMAMUX routing uses the same timer update event mappings.
## Memory Usage
### Current
- Output: ~272 bytes per timer (4 channels * 17 words * 4 bytes, cache-aligned)
- Capture: ~256 bytes per timer (4 channels * 32 samples * 2 bytes)
### Bitbang
- Output: ~1284 bytes per port group (321 words * 4 bytes, cache-aligned)
- Capture: ~1024 bytes per port group (512 samples * 2 bytes, cache-aligned)
- Scales with number of port groups, not number of motors
- Higher per-group cost, but acceptable for H7 (1MB+ SRAM)
## Open Questions / Risks
1. **GPIO output speed**: BSRR writes through AHB4 bus on H7. At 83.3ns per DMA transfer (12MHz), is there enough bus bandwidth? Should be fine - AHB4 runs at 240MHz, and BSRR writes are single-cycle.
2. **DMA priority vs other peripherals**: SPI1 (IMU) is on DMA1. Timer DMA is already high priority. No change expected.
3. **GPIO input threshold**: When reading IDR for bidir, the input threshold depends on GPIO input configuration (Schmitt trigger, pull-up/down). The current capture approach uses timer input capture which has different input characteristics. May need to configure GPIO pull-up to match idle-high behavior.
4. **Signal integrity**: Timer PWM output has precise edge timing locked to the timer clock. BSRR writes via DMA may have slight jitter due to bus arbitration. This is likely negligible (< 10ns on H7) but should be verified.
5. **OTYPER configuration**: For bidirectional DShot, the pin needs to be open-drain (or at least not actively driven when in input mode). The MODER switch to input (00) handles this, but verify that switching MODER during/after a frame doesn't cause glitches.
6. **Cache coherency**: BSRR output buffers need dcache clean before DMA. IDR capture buffers need dcache invalidate after DMA. Same pattern as current code.
## Implementation Order
1. **Port group initialization**: Parse `timer_io_channels[]` to build `port_group_t` structures grouped by GPIO port instead of timer
2. **Output-only DShot**: Implement BSRR buffer building and DMA output. Verify with logic analyzer that DShot frames are correct
3. **Bidirectional capture**: Implement IDR sampling and per-pin edge extraction. Verify GCR decode produces valid eRPM
4. **Integration**: Wire up to the existing `up_dshot_*` API so `DShot.cpp` works unchanged
5. **Testing**: Compare eRPM data quality (CRC error rate, update rate) vs current implementation
## Reference: Betaflight Bitbang Implementation
- [Betaflight dshot_bitbang.c](https://github.com/betaflight/betaflight/blob/master/src/platform/STM32/dshot_bitbang.c)
- [Betaflight dshot_bitbang_impl.h](https://github.com/betaflight/betaflight/blob/master/src/main/drivers/dshot_bitbang_impl.h)
- [Original GPIO banging PR #7446](https://github.com/betaflight/betaflight/pull/7446)
- [Bidirectional bitbang PR #8779](https://github.com/betaflight/betaflight/pull/8779)
## Reference: Current PX4 Implementation Files
- DShot platform layer: `platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c`
- IO timer layer: `platforms/nuttx/src/px4/stm/stm32_common/io_pins/io_timer.c`
- IO timer struct defs: `platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/io_timer.h`
- GPIO/pin helpers: `platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/hw_description.h`
- H7 timer/DMA descriptions: `platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer_hw_description.h`
- H7 GPIO register defs: NuttX `arch/arm/src/stm32h7/stm32_gpio.h` (GPIO_PORT_MASK, GPIO_PIN_MASK, g_gpiobase[])
- H7 GPIO HW registers: NuttX `arch/arm/src/stm32h7/hardware/stm32h7x3xx_gpio.h` (STM32_GPIO_MODER_OFFSET, etc.)
- DShot API header: `src/drivers/drv_dshot.h`
- DShot driver module: `src/drivers/dshot/DShot.cpp`
## Reference: Test Target (ARK FPV)
- Timer config: `boards/ark/fpv/src/timer_config.cpp`
- DMA map: `boards/ark/fpv/nuttx-config/include/board_dma_map.h`
- Board config: `boards/ark/fpv/src/board_config.h`
+433
View File
@@ -0,0 +1,433 @@
#!/usr/bin/env python3
"""
BDShot Timing Jitter Analyzer
Analyzes BDShot (Bidirectional DShot) signal timing from Saleae Logic Analyzer
CSV exports. Measures scheduling consistency and jitter in PX4 flight controller
DShot output timing.
Usage:
python bdshot_analyzer.py capture.csv
python bdshot_analyzer.py capture.csv --dshot-rate 300 --loop-rate 800
python bdshot_analyzer.py capture.csv --channel-a 0 --channel-b 1
Arguments:
input_file Path to Saleae CSV export
--dshot-rate DShot variant: 150/300/600/1200 (default: 300)
--loop-rate Expected loop rate in Hz (default: 800)
--channel-a CSV column index for first channel (default: 0)
--channel-b CSV column index for second channel (default: 1)
--no-plots Disable histogram display
--verbose Enable verbose debugging output
Capture Setup:
1. Connect Saleae to two BDShot signals from different timers
(e.g., Motor 1 from Timer1, Motor 5 from Timer2)
2. Sample rate: 24+ MS/s for DShot300
3. Export as CSV: File -> Export Raw Data -> CSV
Interpreting Results:
- Frame Intervals: Should cluster tightly around expected loop period
- Inter-Channel Gap: Measures sequential DMA scheduling overhead
- Jitter: Small std dev is typical for well-behaved systems
Dependencies: numpy, matplotlib
"""
import argparse
import csv
import sys
from dataclasses import dataclass
from pathlib import Path
import numpy as np
# Try to import matplotlib, but allow running without it
try:
import matplotlib.pyplot as plt
HAS_MATPLOTLIB = True
except ImportError:
HAS_MATPLOTLIB = False
# DShot bit periods in microseconds
DSHOT_BIT_PERIODS = {
150: 6.67,
300: 3.33,
600: 1.67,
1200: 0.83,
}
@dataclass
class BDShotTransaction:
"""Represents a single BDShot transaction (command + response)."""
start: float # Timestamp of first falling edge (seconds)
end: float # Timestamp of final rising edge before idle (seconds)
@property
def duration_us(self) -> float:
"""Transaction duration in microseconds."""
return (self.end - self.start) * 1_000_000
@dataclass
class ChannelStats:
"""Statistics for a single channel's frame intervals."""
channel_name: str
count: int
min_us: float
max_us: float
mean_us: float
std_us: float
expected_us: float
@property
def min_jitter_us(self) -> float:
return self.min_us - self.expected_us
@property
def max_jitter_us(self) -> float:
return self.max_us - self.expected_us
@property
def mean_jitter_us(self) -> float:
return self.mean_us - self.expected_us
@dataclass
class GapStats:
"""Statistics for inter-channel gaps."""
count: int
min_us: float
max_us: float
mean_us: float
std_us: float
def parse_csv(filepath: Path, channel_a_idx: int, channel_b_idx: int, verbose: bool = False):
"""
Parse Saleae CSV export and extract edges for each channel.
Returns:
Tuple of (edges_a, edges_b) where each is a list of (timestamp, new_state) tuples.
"""
edges_a, edges_b = [], []
prev_a, prev_b = None, None
ch_a_col, ch_b_col = channel_a_idx + 1, channel_b_idx + 1 # +1 for time column
with open(filepath, 'r', newline='') as f:
reader = csv.reader(f)
header = next(reader)
if verbose:
print(f"CSV Header: {header}")
print(f"Using columns: time=0, ch_a={ch_a_col} ({header[ch_a_col]}), "
f"ch_b={ch_b_col} ({header[ch_b_col]})")
if ch_a_col >= len(header) or ch_b_col >= len(header):
raise ValueError(
f"Channel indices out of range. CSV has {len(header)-1} channels. "
f"Requested channel_a={channel_a_idx}, channel_b={channel_b_idx}"
)
for row_num, row in enumerate(reader, start=2):
try:
timestamp = float(row[0])
state_a, state_b = int(row[ch_a_col]), int(row[ch_b_col])
# Record edges (state changes) or initial LOW state
if (prev_a is not None and state_a != prev_a) or (prev_a is None and state_a == 0):
edges_a.append((timestamp, state_a))
if (prev_b is not None and state_b != prev_b) or (prev_b is None and state_b == 0):
edges_b.append((timestamp, state_b))
prev_a, prev_b = state_a, state_b
except (ValueError, IndexError) as e:
if verbose:
print(f"Warning: Skipping malformed row {row_num}: {e}")
if verbose:
print(f"Parsed {len(edges_a)} edges for channel A, {len(edges_b)} edges for channel B")
return edges_a, edges_b
def detect_transactions(edges, idle_threshold_us: float, verbose: bool = False):
"""
Detect BDShot transactions from edge list.
A transaction starts with a falling edge after an idle period and ends
when the line returns HIGH and stays HIGH for > idle_threshold_us.
"""
if not edges:
return []
idle_threshold_s = idle_threshold_us / 1_000_000
transactions = []
tx_start = None
last_rising = None
for i, (timestamp, state) in enumerate(edges):
if state == 0: # Falling edge - start transaction if idle
if tx_start is None and (last_rising is None or timestamp - last_rising > idle_threshold_s):
tx_start = timestamp
elif tx_start is not None: # Rising edge with active transaction
last_rising = timestamp
# Complete transaction if next edge is far away or this is the last edge
next_gap = edges[i + 1][0] - timestamp if i + 1 < len(edges) else float('inf')
if next_gap > idle_threshold_s:
transactions.append(BDShotTransaction(start=tx_start, end=timestamp))
tx_start = None
else:
last_rising = timestamp
if verbose:
print(f"Detected {len(transactions)} transactions")
if transactions:
durations = [tx.duration_us for tx in transactions]
print(f" Duration range: {min(durations):.1f} - {max(durations):.1f} us")
return transactions
def compute_channel_stats(transactions, channel_name: str, expected_interval_us: float):
"""Compute frame interval statistics for a channel."""
if len(transactions) < 2:
raise ValueError(f"Need at least 2 transactions to compute intervals, got {len(transactions)}")
intervals_us = np.diff([tx.start for tx in transactions]) * 1_000_000
stats = ChannelStats(
channel_name=channel_name,
count=len(intervals_us),
min_us=float(np.min(intervals_us)),
max_us=float(np.max(intervals_us)),
mean_us=float(np.mean(intervals_us)),
std_us=float(np.std(intervals_us)),
expected_us=expected_interval_us,
)
return stats, intervals_us
def compute_inter_channel_gaps(transactions_a, transactions_b, expected_interval_us: float,
verbose: bool = False):
"""Compute inter-channel gap statistics (CH_A end -> CH_B start)."""
gaps = []
max_reasonable_gap_us = expected_interval_us * 0.5
b_idx = 0
for tx_a in transactions_a:
# Find first CH_B transaction that starts after this CH_A ends
while b_idx < len(transactions_b) and transactions_b[b_idx].start <= tx_a.end:
b_idx += 1
if b_idx >= len(transactions_b):
break
gap_us = (transactions_b[b_idx].start - tx_a.end) * 1_000_000
if 0 < gap_us < max_reasonable_gap_us:
gaps.append(gap_us)
if verbose:
print(f"Inter-channel gap matching: {len(gaps)} matched")
if not gaps:
raise ValueError("No valid inter-channel gaps found")
gaps_arr = np.array(gaps)
stats = GapStats(
count=len(gaps_arr),
min_us=float(np.min(gaps_arr)),
max_us=float(np.max(gaps_arr)),
mean_us=float(np.mean(gaps_arr)),
std_us=float(np.std(gaps_arr)),
)
return stats, gaps_arr
def _plot_histogram(ax, data, title: str, xlabel: str, expected_value=None, stats_text=None):
"""Plot a histogram on the given axes."""
bin_count = min(100, max(20, len(data) // 100)) if np.ptp(data) > 0 else 20
ax.hist(data, bins=bin_count, edgecolor='black', alpha=0.7)
ax.set_title(title, fontsize=12, fontweight='bold')
ax.set_xlabel(xlabel, fontsize=10)
ax.set_ylabel('Count', fontsize=10)
if expected_value is not None:
ax.axvline(expected_value, color='red', linestyle='--', linewidth=2,
label=f'Expected: {expected_value:.2f} us')
ax.axvline(np.mean(data), color='green', linestyle='-', linewidth=2,
label=f'Mean: {np.mean(data):.2f} us')
if stats_text:
ax.text(0.98, 0.97, stats_text, transform=ax.transAxes, fontsize=9,
verticalalignment='top', horizontalalignment='right',
bbox=dict(boxstyle='round', facecolor='wheat', alpha=0.8), family='monospace')
ax.legend(loc='upper left', fontsize=8)
ax.grid(True, alpha=0.3)
def generate_combined_histogram(intervals_a, intervals_b, gaps, stats_a, stats_b,
gap_stats, expected_interval_us: float, dshot_rate: int):
"""Generate a combined figure with all histograms."""
if not HAS_MATPLOTLIB:
return None
fig = plt.figure(figsize=(14, 10))
gs = fig.add_gridspec(2, 2, height_ratios=[1, 1], hspace=0.3, wspace=0.25)
ax_a, ax_b, ax_gap = fig.add_subplot(gs[0, 0]), fig.add_subplot(gs[0, 1]), fig.add_subplot(gs[1, :])
def stats_text(s):
return format_stats_text(s.min_us, s.max_us, s.mean_us, s.std_us, s.count)
_plot_histogram(ax_a, intervals_a, "Channel A Frame Intervals", "Interval (us)",
expected_value=expected_interval_us, stats_text=stats_text(stats_a))
_plot_histogram(ax_b, intervals_b, "Channel B Frame Intervals", "Interval (us)",
expected_value=expected_interval_us, stats_text=stats_text(stats_b))
if len(gaps) > 0:
_plot_histogram(ax_gap, gaps, "Inter-Channel Gap (CH_A End -> CH_B Start)",
"Gap (us)", stats_text=stats_text(gap_stats))
else:
ax_gap.text(0.5, 0.5, "No inter-channel gap data available",
ha='center', va='center', transform=ax_gap.transAxes)
ax_gap.set_title("Inter-Channel Gap (CH_A End -> CH_B Start)")
fig.suptitle(f"BDShot Timing Analysis (DShot{dshot_rate})", fontsize=14, fontweight='bold', y=0.98)
return fig
def format_stats_text(min_val: float, max_val: float, mean_val: float,
std_val: float, count: int) -> str:
"""Format statistics as a text block for histogram annotation."""
return (f"Count: {count}\n"
f"Min: {min_val:.2f} us\n"
f"Max: {max_val:.2f} us\n"
f"Mean: {mean_val:.2f} us\n"
f"Std: {std_val:.2f} us")
def print_report(input_file: Path, dshot_rate: int, loop_rate: float,
capture_duration: float, tx_count_a: int, tx_count_b: int,
stats_a: ChannelStats, stats_b: ChannelStats, gap_stats: GapStats):
"""Print the analysis report to console."""
bit_period = DSHOT_BIT_PERIODS.get(dshot_rate, 3.33)
expected_interval = 1_000_000 / loop_rate
print(f"""
BDShot Timing Analysis
{"=" * 60}
Input: {input_file}
DShot Rate: {dshot_rate} (bit period: {bit_period:.2f} us)
Expected Loop Rate: {loop_rate:.0f} Hz ({expected_interval:.2f} us interval)
Capture Duration: {capture_duration:.2f} s
Transactions Detected: CH_A={tx_count_a}, CH_B={tx_count_b}
""")
def print_channel_stats(name: str, s: ChannelStats):
print(f"{name} Frame Intervals")
print("-" * 40)
print(f" Count: {s.count}")
print(f" Min: {s.min_us:.2f} us ({s.min_jitter_us:+.2f} us from nominal)")
print(f" Max: {s.max_us:.2f} us ({s.max_jitter_us:+.2f} us from nominal)")
print(f" Mean: {s.mean_us:.2f} us ({s.mean_jitter_us:+.2f} us from nominal)")
print(f" Std Dev: {s.std_us:.2f} us\n")
print_channel_stats("Channel A", stats_a)
print_channel_stats("Channel B", stats_b)
print(f"""Inter-Channel Gap (CH_A End -> CH_B Start)
{"-" * 40}
Count: {gap_stats.count}
Min: {gap_stats.min_us:.2f} us
Max: {gap_stats.max_us:.2f} us
Mean: {gap_stats.mean_us:.2f} us
Std Dev: {gap_stats.std_us:.2f} us
""")
def fatal(msg: str):
"""Print error and exit."""
print(f"Error: {msg}", file=sys.stderr)
sys.exit(1)
def main():
parser = argparse.ArgumentParser(
description="Analyze BDShot timing from Saleae Logic Analyzer CSV exports",
formatter_class=argparse.RawDescriptionHelpFormatter,
epilog="Examples:\n %(prog)s capture.csv\n %(prog)s capture.csv --dshot-rate 300 --loop-rate 800"
)
parser.add_argument('input_file', type=Path, help='Path to Saleae CSV export')
parser.add_argument('--dshot-rate', type=int, default=300, choices=[150, 300, 600, 1200],
help='DShot variant (default: 300)')
parser.add_argument('--loop-rate', type=float, default=800, help='Expected loop rate in Hz (default: 800)')
parser.add_argument('--channel-a', type=int, default=0, help='CSV column index for first channel (default: 0)')
parser.add_argument('--channel-b', type=int, default=1, help='CSV column index for second channel (default: 1)')
parser.add_argument('--no-plots', action='store_true', help='Disable histogram display')
parser.add_argument('--verbose', '-v', action='store_true', help='Enable verbose output for debugging')
args = parser.parse_args()
if not args.input_file.exists():
fatal(f"Input file not found: {args.input_file}")
# Calculate timing parameters
bit_period_us = DSHOT_BIT_PERIODS.get(args.dshot_rate, 3.33)
idle_threshold_us = max(50.0, bit_period_us * 15) # Must exceed turnaround gap (~25-30us)
expected_interval_us = 1_000_000 / args.loop_rate
if args.verbose:
print(f"Bit period: {bit_period_us:.2f} us\nIdle threshold: {idle_threshold_us:.2f} us\n"
f"Expected interval: {expected_interval_us:.2f} us\n")
# Parse CSV
print(f"Parsing {args.input_file}...")
try:
edges_a, edges_b = parse_csv(args.input_file, args.channel_a, args.channel_b, args.verbose)
except Exception as e:
fatal(f"parsing CSV: {e}")
if not edges_a or not edges_b:
fatal("No edges found in one or both channels")
# Detect transactions
print("Detecting transactions...")
transactions_a = detect_transactions(edges_a, idle_threshold_us, args.verbose)
transactions_b = detect_transactions(edges_b, idle_threshold_us, args.verbose)
for name, txns in [("A", transactions_a), ("B", transactions_b)]:
if len(txns) < 2:
fatal(f"Insufficient transactions in channel {name} ({len(txns)})")
# Calculate capture duration
all_txns = transactions_a + transactions_b
capture_duration = max(tx.end for tx in all_txns) - min(tx.start for tx in all_txns)
# Compute statistics
print("Computing statistics...")
stats_a, intervals_a = compute_channel_stats(transactions_a, "Channel A", expected_interval_us)
stats_b, intervals_b = compute_channel_stats(transactions_b, "Channel B", expected_interval_us)
try:
gap_stats, gaps = compute_inter_channel_gaps(transactions_a, transactions_b,
expected_interval_us, args.verbose)
except ValueError as e:
print(f"Warning: {e}", file=sys.stderr)
gap_stats = GapStats(count=0, min_us=0, max_us=0, mean_us=0, std_us=0)
gaps = np.array([])
print_report(args.input_file, args.dshot_rate, args.loop_rate, capture_duration,
len(transactions_a), len(transactions_b), stats_a, stats_b, gap_stats)
if not args.no_plots and HAS_MATPLOTLIB:
generate_combined_histogram(intervals_a, intervals_b, gaps, stats_a, stats_b,
gap_stats, expected_interval_us, args.dshot_rate)
plt.show()
if __name__ == '__main__':
main()
-6
View File
@@ -28,16 +28,10 @@ CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
CONFIG_DRIVERS_IMU_MURATA_SCH16T=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
CONFIG_DRIVERS_MAGNETOMETER_LSM303AGR=y
CONFIG_DRIVERS_MAGNETOMETER_RM3100=y
CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT=y
-3
View File
@@ -419,9 +419,6 @@
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board has 4 DMA channels available for bidirectional dshot */
#define BOARD_DMA_NUM_DSHOT_CHANNELS 4
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
+2
View File
@@ -14,6 +14,7 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DSHOT_BITBANG=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
@@ -59,6 +60,7 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
Binary file not shown.
+18
View File
@@ -0,0 +1,18 @@
4001_quad_x
4050_generic_250
6001_hexa_x
12001_octo_cox
13100_generic_vtol_tiltrotor
5001_quad_+
24001_dodeca_cox
2100_standard_plane
13000_generic_vtol_standard
4601_droneblocks_dexi_5
11001_hexa_cox
14001_generic_mc_with_tilt
16001_helicopter
9001_octo_+
7001_hexa_+
3000_generic_wing
13200_generic_vtol_tailsitter
13030_generic_vtol_quad_tiltrotor
-3
View File
@@ -307,9 +307,6 @@
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board has 3 DMA channels available for bidirectional dshot */
#define BOARD_DMA_NUM_DSHOT_CHANNELS 3
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
-3
View File
@@ -309,9 +309,6 @@
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board has 4 DMA channels available for bidirectional dshot */
#define BOARD_DMA_NUM_DSHOT_CHANNELS 4
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
@@ -58,11 +58,13 @@
//#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */
//#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */
// Assigned in timer_config.cpp
// TODO
// Timer 4 /* 7 DMA1:32 TIM4UP */
// Timer 5 /* 8 DMA1:50 TIM5UP */
// Dynamically assigned in timer_config.cpp for DShot (allocated/freed per cycle):
// Timer 1 TIM1UP (burst) + TIM1CH1-4 (capture)
// Timer 2 TIM2UP (burst) + TIM2CH1-4 (capture)
// Timer 3 TIM3UP (burst) + TIM3CH1-4 (capture)
// Timer 4 TIM4UP (burst) + TIM4CH1-3 (capture, CH4 has no DMA)
// Timer 5 TIM5UP (burst) + TIM5CH1-4 (capture)
// Timer 15 - no TIM15UP DMA, cannot do DShot
// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned
// V
@@ -38,18 +38,20 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
initIOTimer(Timer::Timer15),
initIOTimer(Timer::Timer3),
initIOTimer(Timer::Timer2),
initIOTimer(Timer::Timer15), // Note: Timer15 has no TIM_UP DMA on STM32H7, cannot do DShot
initIOTimer(Timer::Timer3, DMA{DMA::Index1}),
initIOTimer(Timer::Timer2, DMA{DMA::Index1}),
};
// Note: Timer4 Channel4 has no DMAMUX mapping on STM32H7, so BDShot telemetry capture
// is not available on that channel. DShot output still works (uses TIM_UP DMA for burst).
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), // no BDShot telemetry readback
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}),
+2
View File
@@ -69,6 +69,8 @@ set(msg_files
DistanceSensorModeChangeRequest.msg
DronecanNodeStatus.msg
Ekf2Timestamps.msg
EscEepromRead.msg
EscEepromWrite.msg
EscReport.msg
EscStatus.msg
EstimatorAidSource1d.msg
+7
View File
@@ -0,0 +1,7 @@
uint64 timestamp # [us] Time since system start
uint8 firmware # ESC firmware type (see ESC_FIRMWARE enum in MAVLink)
uint8 index # [-] Index of the ESC (0 = ESC1, 1 = ESC2, etc.)
uint16 length # [-] Length of valid data
uint8[192] data # [-] Raw ESC EEPROM data
uint8 ORB_QUEUE_LENGTH = 8 # To support 8 queued up responses
+8
View File
@@ -0,0 +1,8 @@
uint64 timestamp # [us] Time since system start
uint8 firmware # [-] ESC firmware type (see ESC_FIRMWARE enum in MAVLink)
uint8 index # [-]Index of the ESC (0 = ESC1, 1 = ESC2, etc, 255 = All)
uint16 length # [-]Length of valid data
uint8[64] data # [-]Raw ESC EEPROM data
uint32[2] write_mask # [-] Bitmask indicating which bytes in the data array should be written (max 64 values)
uint8 ORB_QUEUE_LENGTH = 8 # To support 8 queued up requests
+24 -23
View File
@@ -1,15 +1,16 @@
uint64 timestamp # time since system start (microseconds)
uint32 esc_errorcount # Number of reported errors by ESC - if supported
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported
float32 esc_voltage # Voltage measured from current ESC [V] - if supported
float32 esc_current # Current measured from current ESC [A] - if supported
float32 esc_temperature # Temperature measured from current ESC [degC] - if supported
uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver)
uint8 esc_cmdcount # Counter of number of commands
uint64 timestamp # [us] Time since system start
uint8 esc_state # State of ESC - depend on Vendor
uint32 esc_errorcount # [-] Number of reported errors by ESC - if supported
int32 esc_rpm # [rpm] Motor RPM, negative for reverse rotation - if supported
float32 esc_voltage # [V] Voltage measured from current ESC - if supported
float32 esc_current # [A] Current measured from current ESC - if supported
float32 esc_temperature # [degC] Temperature measured from current ESC - if supported
uint8 esc_address # [-] Address of current ESC (in most cases 1-8 / must be set by driver)
uint8 esc_cmdcount # [-] Counter of number of commands
uint8 actuator_function # actuator output function (one of Motor1...MotorN)
uint8 esc_state # [-] State of ESC - depend on Vendor
uint8 actuator_function # [-] Actuator output function (one of Motor1...MotorN)
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
uint8 ACTUATOR_FUNCTION_MOTOR2 = 102
@@ -24,17 +25,17 @@ uint8 ACTUATOR_FUNCTION_MOTOR10 = 110
uint8 ACTUATOR_FUNCTION_MOTOR11 = 111
uint8 ACTUATOR_FUNCTION_MOTOR12 = 112
uint16 failures # Bitmask to indicate the internal ESC faults
int8 esc_power # Applied power 0-100 in % (negative values reserved)
uint16 failures # [@enum FAILURE] Bitmask to indicate the internal ESC faults
int8 esc_power # [%] [@range 0,100] Applied power (negative values reserved)
uint8 FAILURE_OVER_CURRENT = 0 # (1 << 0)
uint8 FAILURE_OVER_VOLTAGE = 1 # (1 << 1)
uint8 FAILURE_MOTOR_OVER_TEMPERATURE = 2 # (1 << 2)
uint8 FAILURE_OVER_RPM = 3 # (1 << 3)
uint8 FAILURE_INCONSISTENT_CMD = 4 # (1 << 4) Set if ESC received an inconsistent command (i.e out of boundaries)
uint8 FAILURE_MOTOR_STUCK = 5 # (1 << 5)
uint8 FAILURE_GENERIC = 6 # (1 << 6)
uint8 FAILURE_MOTOR_WARN_TEMPERATURE = 7 # (1 << 7)
uint8 FAILURE_WARN_ESC_TEMPERATURE = 8 # (1 << 8)
uint8 FAILURE_OVER_ESC_TEMPERATURE = 9 # (1 << 9)
uint8 ESC_FAILURE_COUNT = 10 # Counter - keep it as last element!
uint8 FAILURE_OVER_CURRENT = 0 # (1 << 0)
uint8 FAILURE_OVER_VOLTAGE = 1 # (1 << 1)
uint8 FAILURE_MOTOR_OVER_TEMPERATURE = 2 # (1 << 2)
uint8 FAILURE_OVER_RPM = 3 # (1 << 3)
uint8 FAILURE_INCONSISTENT_CMD = 4 # (1 << 4) Set if ESC received an inconsistent command (i.e out of boundaries)
uint8 FAILURE_MOTOR_STUCK = 5 # (1 << 5)
uint8 FAILURE_GENERIC = 6 # (1 << 6)
uint8 FAILURE_MOTOR_WARN_TEMPERATURE = 7 # (1 << 7)
uint8 FAILURE_WARN_ESC_TEMPERATURE = 8 # (1 << 8)
uint8 FAILURE_OVER_ESC_TEMPERATURE = 9 # (1 << 9)
uint8 ESC_FAILURE_COUNT = 10 # Counter - keep it as last element!
+26 -22
View File
@@ -1,28 +1,32 @@
uint64 timestamp # time since system start (microseconds)
uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs
uint64 timestamp # [us] Time since system start
uint8 CONNECTED_ESC_MAX = 12 # The number of ESCs supported (Motor1-Motor12)
uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC
uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC
uint8 ESC_CONNECTION_TYPE_ONESHOT = 2 # One Shot PPM
uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C
uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus
uint8 ESC_CONNECTION_TYPE_DSHOT = 5 # DShot
uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC
uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC
uint8 ESC_CONNECTION_TYPE_ONESHOT = 2 # One Shot PPM
uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C
uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus
uint8 ESC_CONNECTION_TYPE_DSHOT = 5 # DShot
uint16 counter # incremented by the writing thread everytime new data is stored
uint16 counter # [-] Incremented by the writing thread everytime new data is stored
uint8 esc_count # number of connected ESCs
uint8 esc_connectiontype # how ESCs connected to the system
uint8 esc_count # [-] Number of connected ESCs
uint8 esc_connectiontype # [@enum ESC_CONNECTION_TYPE] How ESCs connected to the system
uint8 esc_online_flags # Bitmask indicating which ESC is online/offline
# esc_online_flags bit 0 : Set to 1 if ESC0 is online
# esc_online_flags bit 1 : Set to 1 if ESC1 is online
# esc_online_flags bit 2 : Set to 1 if ESC2 is online
# esc_online_flags bit 3 : Set to 1 if ESC3 is online
# esc_online_flags bit 4 : Set to 1 if ESC4 is online
# esc_online_flags bit 5 : Set to 1 if ESC5 is online
# esc_online_flags bit 6 : Set to 1 if ESC6 is online
# esc_online_flags bit 7 : Set to 1 if ESC7 is online
uint16 esc_online_flags # Bitmask indicating which ESC is online/offline (in motor order)
# esc_online_flags bit 0 : Set to 1 if Motor1 is online
# esc_online_flags bit 1 : Set to 1 if Motor2 is online
# esc_online_flags bit 2 : Set to 1 if Motor3 is online
# esc_online_flags bit 3 : Set to 1 if Motor4 is online
# esc_online_flags bit 4 : Set to 1 if Motor5 is online
# esc_online_flags bit 5 : Set to 1 if Motor6 is online
# esc_online_flags bit 6 : Set to 1 if Motor7 is online
# esc_online_flags bit 7 : Set to 1 if Motor8 is online
# esc_online_flags bit 8 : Set to 1 if Motor9 is online
# esc_online_flags bit 9 : Set to 1 if Motor10 is online
# esc_online_flags bit 10: Set to 1 if Motor11 is online
# esc_online_flags bit 11: Set to 1 if Motor12 is online
uint8 esc_armed_flags # Bitmask indicating which ESC is armed. For ESC's where the arming state is not known (returned by the ESC), the arming bits should always be set.
uint16 esc_armed_flags # [-] Bitmask indicating which ESC is armed (in motor order)
EscReport[8] esc
EscReport[12] esc
+2 -1
View File
@@ -10,7 +10,8 @@ uint64 timestamp_sample # [us] Sampling timestamp of the data this control resp
uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 #
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
uint8 ACTUATOR_FUNCTION_MOTOR12 = 112
uint8 NUM_CONTROLS = 12 #
float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors)
+8
View File
@@ -80,6 +80,7 @@ uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information
uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)|
uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function|
uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function|
uint16 VEHICLE_CMD_ESC_REQUEST_EEPROM = 312 # Request EEPROM data from an ESC. |ESC index|Firmware type (ESC_FIRMWARE enum)|Unused|Unused||Unused|Unused|
uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm.
uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks.
uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes.
@@ -129,6 +130,13 @@ uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location.
uint8 VEHICLE_ROI_TARGET = 4 # Point toward target.
uint8 VEHICLE_ROI_ENUM_END = 5
uint8 ACTUATOR_CONFIGURATION_NONE = 0 # Do nothing.
uint8 ACTUATOR_CONFIGURATION_BEEP = 1 # Command the actuator to beep now.
uint8 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2 # Permanently set the actuator (ESC) to 3D mode (reversible thrust).
uint8 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3 # Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust).
uint8 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4 # Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise).
uint8 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5 # Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1).
uint8 PARACHUTE_ACTION_DISABLE = 0
uint8 PARACHUTE_ACTION_ENABLE = 1
uint8 PARACHUTE_ACTION_RELEASE = 2
+25 -18
View File
@@ -321,8 +321,10 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
}
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
int up_dshot_init(uint32_t channel_mask, uint32_t bdshot_channel_mask, unsigned dshot_pwm_freq, bool edt_enable)
{
(void)edt_enable; // Not implemented
/* Calculate dshot timings based on dshot_pwm_freq */
dshot_tcmp = 0x2F00 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2) - 1) & 0xFF);
dshot_speed = dshot_pwm_freq;
@@ -360,7 +362,7 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi
imxrt_config_gpio(timer_io_channels[channel].dshot.pinmux | IOMUX_PULL_UP);
if (enable_bidirectional_dshot) {
if (bdshot_channel_mask & (1 << channel)) {
dshot_inst[channel].bdshot = true;
dshot_inst[channel].bdshot_training_mask = 0;
dshot_inst[channel].bdshot_tcmp_offset = BDSHOT_TCMP_MIN_OFFSET;
@@ -497,22 +499,12 @@ void up_bdshot_erpm(void)
}
int up_bdshot_num_erpm_ready(void)
int up_bdshot_num_errors(uint8_t channel)
{
int num_ready = 0;
for (unsigned i = 0; i < DSHOT_TIMERS; ++i) {
// We only check that data has been received, rather than if it's valid.
// This ensures data is published even if one channel has bit errors.
if (bdshot_parsed_recv_mask & (1 << i)) {
++num_ready;
}
}
return num_ready;
return dshot_inst[channel].crc_error_cnt + dshot_inst[channel].frame_error_cnt + dshot_inst[channel].no_response_cnt;
}
int up_bdshot_get_erpm(uint8_t channel, int *erpm)
{
if (bdshot_parsed_recv_mask & (1 << channel)) {
@@ -523,7 +515,22 @@ int up_bdshot_get_erpm(uint8_t channel, int *erpm)
return -1;
}
int up_bdshot_channel_status(uint8_t channel)
int up_bdshot_get_extended_telemetry(uint8_t channel, int type, uint8_t *value)
{
// NOT IMPLEMENTED
return -1;
}
int up_bdshot_channel_capture_supported(uint8_t channel)
{
if (channel >= DSHOT_TIMERS) {
return 0;
}
return dshot_inst[channel].init && dshot_inst[channel].bdshot;
}
int up_bdshot_channel_online(uint8_t channel)
{
if (channel < DSHOT_TIMERS) {
return ((dshot_inst[channel].no_response_cnt - dshot_inst[channel].last_no_response_cnt) < BDSHOT_OFFLINE_COUNT);
@@ -538,7 +545,7 @@ void up_bdshot_status(void)
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
if (dshot_inst[channel].init) {
PX4_INFO("Channel %i %s Last erpm %i value", channel, up_bdshot_channel_status(channel) ? "online" : "offline",
PX4_INFO("Channel %i %s Last erpm %i value", channel, up_bdshot_channel_online(channel) ? "online" : "offline",
dshot_inst[channel].erpm);
PX4_INFO("BDSHOT Training done: %s TCMP offset: %d", dshot_inst[channel].bdshot_training_done ? "YES" : "NO",
dshot_inst[channel].bdshot_tcmp_offset);
@@ -601,7 +608,7 @@ uint64_t dshot_expand_data(uint16_t packet)
* bit 12 - dshot telemetry enable/disable
* bits 13-16 - XOR checksum
**/
void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
void dshot_motor_data_set(uint8_t channel, uint16_t throttle, bool telemetry)
{
if (channel < DSHOT_TIMERS && dshot_inst[channel].init) {
uint16_t csum_data;
@@ -31,7 +31,13 @@
#
############################################################################
if(CONFIG_DSHOT_BITBANG)
set(DSHOT_SRC dshot_bitbang.c)
else()
set(DSHOT_SRC dshot.c)
endif()
px4_add_library(arch_dshot
dshot.c
${DSHOT_SRC}
)
target_compile_options(arch_dshot PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
+57 -51
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -31,11 +31,6 @@
*
****************************************************************************/
/**
* @file drv_dshot.h
*
*/
#pragma once
#include <px4_platform_common/defines.h>
@@ -48,39 +43,40 @@
__BEGIN_DECLS
typedef enum {
DShot_cmd_motor_stop = 0,
DShot_cmd_beacon1,
DShot_cmd_beacon2,
DShot_cmd_beacon3,
DShot_cmd_beacon4,
DShot_cmd_beacon5,
DShot_cmd_esc_info, // V2 includes settings
DShot_cmd_spin_direction_1,
DShot_cmd_spin_direction_2,
DShot_cmd_3d_mode_off,
DShot_cmd_3d_mode_on,
DShot_cmd_settings_request, // Currently not implemented
DShot_cmd_save_settings,
DShot_cmd_spin_direction_normal = 20,
DShot_cmd_spin_direction_reversed = 21,
DShot_cmd_led0_on, // BLHeli32 only
DShot_cmd_led1_on, // BLHeli32 only
DShot_cmd_led2_on, // BLHeli32 only
DShot_cmd_led3_on, // BLHeli32 only
DShot_cmd_led0_off, // BLHeli32 only
DShot_cmd_led1_off, // BLHeli32 only
DShot_cmd_led2_off, // BLHeli32 only
DShot_cmd_led4_off, // BLHeli32 only
DShot_cmd_audio_stream_mode_on_off = 30, // KISS audio Stream mode on/off
DShot_cmd_silent_mode_on_off = 31, // KISS silent Mode on/off
DShot_cmd_signal_line_telemetry_disable = 32,
DShot_cmd_signal_line_continuous_erpm_telemetry = 33,
DShot_cmd_MAX = 47, // >47 are throttle values
DShot_cmd_MIN_throttle = 48,
DShot_cmd_MAX_throttle = 2047
} dshot_command_t;
// https://brushlesswhoop.com/dshot-and-bidirectional-dshot/#special-commands
enum {
DSHOT_CMD_MOTOR_STOP = 0,
DSHOT_CMD_BEEP1 = 1,
DSHOT_CMD_ESC_INFO = 6,
DSHOT_CMD_SPIN_DIRECTION_1 = 7,
DSHOT_CMD_SPIN_DIRECTION_2 = 8,
DSHOT_CMD_3D_MODE_OFF = 9,
DSHOT_CMD_3D_MODE_ON = 10,
DSHOT_CMD_SAVE_SETTINGS = 12,
DSHOT_EXTENDED_TELEMETRY_ENABLE = 13,
DSHOT_CMD_ENTER_PROGRAMMING_MODE = 36,
DSHOT_CMD_EXIT_PROGRAMMING_MODE = 37,
DSHOT_CMD_MAX = 47, // >47 are throttle values
DSHOT_CMD_MIN_THROTTLE = 48,
DSHOT_CMD_MAX_THROTTLE = 2047
};
// Extended DShot Telemetry
enum {
DSHOT_EDT_ERPM = 0x00,
DSHOT_EDT_TEMPERATURE = 0x02, // C
DSHOT_EDT_VOLTAGE = 0x04, // 0.25V per step
DSHOT_EDT_CURRENT = 0x06, // A
DSHOT_EDT_DEBUG1 = 0x08,
DSHOT_EDT_DEBUG2 = 0x0A,
DSHOT_EDT_DEBUG3 = 0x0C,
DSHOT_EDT_STATE_EVENT = 0x0E,
};
struct BDShotTelemetry {
int type;
int32_t value;
};
/**
* Intialise the Dshot outputs using the specified configuration.
@@ -91,12 +87,12 @@ typedef enum {
* @param dshot_pwm_freq Frequency of DSHOT signal. Usually DSHOT150, DSHOT300, or DSHOT600
* @return <0 on error, the initialized channels mask.
*/
__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot);
__EXPORT extern int up_dshot_init(uint32_t channel_mask, uint32_t bdshot_channel_mask, unsigned dshot_pwm_freq, bool edt_enable);
/**
* Set Dshot motor data, used by up_dshot_motor_data_set() and up_dshot_motor_command() (internal method)
*/
__EXPORT extern void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry);
__EXPORT extern void dshot_motor_data_set(uint8_t channel, uint16_t throttle, bool telemetry);
/**
* Set the current dshot throttle value for a channel (motor).
@@ -105,9 +101,9 @@ __EXPORT extern void dshot_motor_data_set(unsigned channel, uint16_t throttle, b
* @param throttle The output dshot throttle value in [0 = DSHOT_DISARM_VALUE, 1 = DSHOT_MIN_THROTTLE, 1999 = DSHOT_MAX_THROTTLE].
* @param telemetry If true, request telemetry from that motor
*/
static inline void up_dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
static inline void up_dshot_motor_data_set(uint8_t channel, uint16_t throttle, bool telemetry)
{
dshot_motor_data_set(channel, throttle + DShot_cmd_MIN_throttle, telemetry);
dshot_motor_data_set(channel, throttle + DSHOT_CMD_MIN_THROTTLE, telemetry);
}
/**
@@ -144,15 +140,11 @@ __EXPORT extern void up_bdshot_status(void);
/**
* Get how many bidirectional erpm channels are ready
*
* When we get the erpm round-robin style, we need to get
* and publish the erpms less often.
*
* @return <0 on error, OK on succes
* Get the total number of errors for a channel
* @param channel Dshot channel
* @return The total number of recorded errors
*/
__EXPORT extern int up_bdshot_num_erpm_ready(void);
__EXPORT extern int up_bdshot_num_errors(uint8_t channel);
/**
* Get bidrectional dshot erpm for a channel
@@ -162,6 +154,14 @@ __EXPORT extern int up_bdshot_num_erpm_ready(void);
*/
__EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm);
/**
* Get bidrectional dshot extended telemetry for a channel
* @param channel Dshot channel
* @param type The type of telemetry value to get
* @param value pointer to write the telemetry value
* @return <0 on error, OK on succes
*/
__EXPORT extern int up_bdshot_get_extended_telemetry(uint8_t channel, int type, uint8_t *value);
/**
* Get bidrectional dshot status for a channel
@@ -169,7 +169,13 @@ __EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm);
* @param erpm pointer to write the erpm value
* @return <0 on error / not supported, 0 on offline, 1 on online
*/
__EXPORT extern int up_bdshot_channel_status(uint8_t channel);
__EXPORT extern int up_bdshot_channel_online(uint8_t channel);
/**
* Check if bidrectional dshot capture is supported for a channel
* @param channel Dshot channel
* @return 0 if not supported (no DMA), 1 if supported
*/
__EXPORT extern int up_bdshot_channel_capture_supported(uint8_t channel);
__END_DECLS
+2
View File
@@ -42,9 +42,11 @@ px4_add_module(
MAIN dshot
COMPILE_FLAGS
-DPARAM_PREFIX="${PARAM_PREFIX}"
# -DDEBUG_BUILD
SRCS
DShot.cpp
DShotTelemetry.cpp
esc/AM32Settings.cpp
DEPENDS
arch_io_pins
arch_dshot
+1046 -576
View File
File diff suppressed because it is too large Load Diff
+147 -92
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019-2022 PX4 Development Team. All rights reserved.
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -39,7 +39,9 @@
#include <uORB/topics/esc_status.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/esc_eeprom_write.h>
#include "DShotCommon.h"
#include "DShotTelemetry.h"
using namespace time_literals;
@@ -48,14 +50,18 @@ using namespace time_literals;
# error "board_config.h needs to define DIRECT_PWM_OUTPUT_CHANNELS"
#endif
/** Dshot PWM frequency, Hz */
static constexpr unsigned int DSHOT150 = 150000u;
static constexpr unsigned int DSHOT300 = 300000u;
static constexpr unsigned int DSHOT600 = 600000u;
static_assert(DSHOT_MAXIMUM_CHANNELS <= 16, "DShot driver uses uint16_t bitmasks");
static constexpr int DSHOT_DISARM_VALUE = 0;
static constexpr int DSHOT_MIN_THROTTLE = 1;
static constexpr int DSHOT_MAX_THROTTLE = 1999;
static constexpr hrt_abstime ESC_INIT_TELEM_DELAY = 5_s;
/// Dshot PWM frequency (Hz)
static constexpr uint32_t DSHOT150 = 150000u;
static constexpr uint32_t DSHOT300 = 300000u;
static constexpr uint32_t DSHOT600 = 600000u;
static constexpr uint16_t DSHOT_DISARM_VALUE = 0;
static constexpr uint16_t DSHOT_MIN_THROTTLE = 1;
static constexpr uint16_t DSHOT_MAX_THROTTLE = 1999;
class DShot final : public ModuleBase<DShot>, public OutputModuleInterface
{
@@ -63,122 +69,171 @@ public:
DShot();
~DShot() override;
/** @see ModuleBase */
// @see ModuleBase
static int custom_command(int argc, char *argv[]);
// @see ModuleBase
int print_status() override;
// @see ModuleBase
static int print_usage(const char *reason = nullptr);
// @see ModuleBase
static int task_spawn(int argc, char *argv[]);
int init();
void mixerChanged() override;
/** @see ModuleBase::print_status() */
int print_status() override;
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
/**
* Send a dshot command to one or all motors
* This is expected to be called from another thread.
* @param num_repetitions number of times to repeat, set at least to 1
* @param motor_index index or -1 for all
* @return 0 on success, <0 error otherwise
*/
int send_command_thread_safe(const dshot_command_t command, const int num_repetitions, const int motor_index);
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
bool telemetry_enabled() const { return _telemetry != nullptr; }
bool updateOutputs(uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
bool updateOutputs(uint16_t *outputs, unsigned num_outputs, unsigned num_control_groups_updated) override;
private:
/** Disallow copy construction and move assignment. */
enum class State {
Disarmed,
Armed
} _state = State::Disarmed;
// Disallow copy construction and move assignment
DShot(const DShot &) = delete;
DShot operator=(const DShot &) = delete;
enum class DShotConfig {
Disabled = 0,
DShot150 = 150,
DShot300 = 300,
DShot600 = 600,
};
struct Command {
dshot_command_t command{};
int num_repetitions{0};
uint8_t motor_mask{0xff};
bool save{false};
bool valid() const { return num_repetitions > 0; }
void clear() { num_repetitions = 0; }
};
int _last_telemetry_index{-1};
uint8_t _actuator_functions[esc_status_s::CONNECTED_ESC_MAX] {};
void enable_dshot_outputs(const bool enabled);
bool initialize_dshot();
void init_telemetry(const char *device, bool swap_rxtx);
int handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data, bool ignore_rpm);
uint16_t esc_armed_mask(uint16_t *outputs, uint8_t num_outputs);
void publish_esc_status(void);
void update_motor_outputs(uint16_t *outputs, int num_outputs);
void update_motor_commands(int num_outputs);
void select_next_command();
int handle_new_bdshot_erpm(void);
bool set_next_telemetry_index(); // Returns true when the telemetry index has wrapped, indicating all configured motors have been sampled.
bool process_serial_telemetry();
bool process_bdshot_telemetry();
void Run() override;
void update_params();
void update_num_motors();
void handle_vehicle_commands();
void consume_esc_data(const EscData &data, TelemetrySource source);
uint16_t calculate_output_value(uint16_t raw, int index);
uint16_t convert_output_to_3d_scaling(uint16_t output);
void Run() override;
void update_params();
// Mavlink command handlers
void handle_vehicle_commands();
void handle_configure_actuator(const vehicle_command_s &command);
void handle_esc_request_eeprom(const vehicle_command_s &command);
// Mixer
MixingOutput _mixing_output{PARAM_PREFIX, DIRECT_PWM_OUTPUT_CHANNELS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
uint32_t _reversible_outputs{};
DShotTelemetry *_telemetry{nullptr};
uORB::PublicationMultiData<esc_status_s> esc_status_pub{ORB_ID(esc_status)};
static char _telemetry_device[20];
static bool _telemetry_swap_rxtx;
static px4::atomic_bool _request_telemetry_init;
px4::atomic<Command *> _new_command{nullptr};
bool _outputs_initialized{false};
bool _outputs_on{false};
bool _bidirectional_dshot_enabled{false};
static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS};
// Actuator-order masks (indexed by output channel)
uint32_t _output_mask{0};
uint32_t _bdshot_output_mask{0};
int _num_motors{0};
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};
perf_counter_t _bdshot_rpm_perf{perf_alloc(PC_COUNT, MODULE_NAME": bdshot rpm")};
perf_counter_t _dshot_telem_perf{perf_alloc(PC_COUNT, MODULE_NAME": dshot telem")};
Command _current_command{};
// Motor-order masks (indexed by motor number: Motor1=0, Motor2=1, etc.)
uint32_t _motor_mask{0};
uint32_t _bdshot_motor_mask{0};
// uORB
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
uint16_t _esc_status_counter{0};
uORB::Subscription _esc_eeprom_write_sub{ORB_ID(esc_eeprom_write)};
uORB::PublicationMultiData<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
esc_status_s _esc_status{};
// Status information
uint32_t _bdshot_telem_online_mask = 0; // Mask indicating telem receive status for bidirectional dshot telem
uint32_t _serial_telem_online_mask = 0; // Mask indicating telem receive status for serial telem
uint32_t _serial_telem_errors[DSHOT_MAXIMUM_CHANNELS] = {};
uint32_t _bdshot_telem_errors[DSHOT_MAXIMUM_CHANNELS] = {};
uint8_t _bdshot_edt_requested_mask = 0;
uint8_t _settings_requested_mask = 0;
// Array of timestamps indicating when the telemetry came online
hrt_abstime _serial_telem_online_timestamps[DSHOT_MAXIMUM_CHANNELS] = {};
hrt_abstime _bdshot_telem_online_timestamps[DSHOT_MAXIMUM_CHANNELS] = {};
// Serial Telemetry
DShotTelemetry _telemetry;
static char _serial_port_path[20];
static bool _telemetry_swap_rxtx;
static px4::atomic_bool _request_telemetry_init;
int _telemetry_motor_index = 0;
uint32_t _telemetry_requested_mask = 0;
hrt_abstime _serial_telem_delay_until = ESC_INIT_TELEM_DELAY;
// Parameters we must load only at init
bool _serial_telemetry_enabled = false;
bool _bdshot_edt_enabled = false;
// Hardware initialization state
bool _hardware_initialized = false;
uint32_t _dshot_frequency = 0;
uint32_t _bdshot_timer_channels = 0;
// Perf counters
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};
perf_counter_t _bdshot_success_perf{perf_alloc(PC_COUNT, MODULE_NAME": bdshot success")};
perf_counter_t _bdshot_error_perf{perf_alloc(PC_COUNT, MODULE_NAME": bdshot error")};
perf_counter_t _serial_telem_success_perf{perf_alloc(PC_COUNT, MODULE_NAME": serial telem success")};
perf_counter_t _serial_telem_error_perf{perf_alloc(PC_COUNT, MODULE_NAME": serial telem error")};
perf_counter_t _serial_telem_timeout_perf{perf_alloc(PC_COUNT, MODULE_NAME": serial telem timeout")};
perf_counter_t _serial_telem_allsampled_perf{perf_alloc(PC_COUNT, MODULE_NAME": serial telem all sampled")};
// Commands
struct DShotCommand {
uint16_t command{};
int num_repetitions{0};
uint16_t motor_mask{(1u << DSHOT_MAXIMUM_CHANNELS) - 1};
bool save{false};
bool expect_response{false};
bool finished() const { return num_repetitions == 0; }
void clear()
{
command = 0;
num_repetitions = 0;
motor_mask = 0;
save = 0;
expect_response = 0;
}
};
DShotCommand _current_command{};
// DShot Programming Mode
enum class ProgrammingState {
Idle,
EnterMode,
SendAddress,
SendValue,
ExitMode
};
esc_eeprom_write_s _esc_eeprom_write{};
bool _dshot_programming_active = {};
uint32_t _settings_written_mask[2] = {};
ProgrammingState _programming_state{ProgrammingState::Idle};
uint16_t _programming_address{};
uint16_t _programming_value{};
// Per-motor pole count
param_t _param_pole_count_handles[12] {};
int get_pole_count(int motor_index);
// Parameters
DEFINE_PARAMETERS(
(ParamInt<px4::params::DSHOT_ESC_TYPE>) _param_dshot_esc_type,
(ParamFloat<px4::params::DSHOT_MIN>) _param_dshot_min,
(ParamBool<px4::params::DSHOT_3D_ENABLE>) _param_dshot_3d_enable,
(ParamInt<px4::params::DSHOT_3D_DEAD_H>) _param_dshot_3d_dead_h,
(ParamInt<px4::params::DSHOT_3D_DEAD_L>) _param_dshot_3d_dead_l,
(ParamInt<px4::params::MOT_POLE_COUNT>) _param_mot_pole_count,
(ParamBool<px4::params::DSHOT_BIDIR_EN>) _param_bidirectional_enable
(ParamBool<px4::params::DSHOT_BIDIR_EDT>) _param_dshot_bidir_edt
)
};
+97
View File
@@ -0,0 +1,97 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <drivers/drv_hrt.h>
#include <board_config.h>
static constexpr int DSHOT_MAXIMUM_CHANNELS = DIRECT_PWM_OUTPUT_CHANNELS;
enum class TelemetrySource {
Serial = 0,
BDShot = 1,
};
struct EscData {
int actuator_channel; // Actuator output channel 0..(DSHOT_MAXIMUM_CHANNELS-1)
int motor_index; // Motor index 0..(CONNECTED_ESC_MAX-1)
hrt_abstime timestamp; // Sample time
TelemetrySource source;
float temperature; // [deg C]
float voltage; // [0.01V]
float current; // [0.01A]
int32_t erpm; // [eRPM]
};
enum class TelemetryStatus {
NotStarted = 0,
NotReady = 1,
Ready = 2,
Timeout = 3,
ParseError = 4,
};
inline int count_set_bits(int mask)
{
int count = 0;
while (mask) {
mask &= mask - 1;
count++;
}
return count;
}
inline uint8_t crc8(const uint8_t *buf, unsigned len)
{
auto update_crc8 = [](uint8_t crc, uint8_t crc_seed) {
uint8_t crc_u = crc ^ crc_seed;
for (unsigned i = 0; i < 8; ++i) {
crc_u = (crc_u & 0x80) ? 0x7 ^ (crc_u << 1) : (crc_u << 1);
}
return crc_u;
};
uint8_t crc = 0;
for (unsigned i = 0; i < len; ++i) {
crc = update_crc8(buf[i], crc);
}
return crc;
}
+202 -276
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019 PX4 Development Team. All rights reserved.
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,6 +34,7 @@
#include "DShotTelemetry.h"
#include <px4_platform_common/log.h>
#include <drivers/drv_dshot.h>
#include <unistd.h>
#include <fcntl.h>
@@ -47,6 +48,14 @@ using namespace time_literals;
DShotTelemetry::~DShotTelemetry()
{
_uart.close();
// Clean up settings handlers
for (int i = 0; i < DSHOT_MAXIMUM_CHANNELS; i++) {
if (_settings_handlers[i]) {
delete _settings_handlers[i];
_settings_handlers[i] = nullptr;
}
}
}
int DShotTelemetry::init(const char *port, bool swap_rxtx)
@@ -76,304 +85,221 @@ int DShotTelemetry::init(const char *port, bool swap_rxtx)
return PX4_OK;
}
int DShotTelemetry::update(int num_motors)
void DShotTelemetry::initSettingsHandlers(ESCType esc_type, uint8_t output_mask)
{
if (_current_motor_index_request == -1) {
// nothing in progress, start a request
_current_motor_index_request = 0;
_current_request_start = 0;
_frame_position = 0;
if (_settings_initialized) {
return;
}
_esc_type = esc_type;
for (uint8_t i = 0; i < DSHOT_MAXIMUM_CHANNELS; i++) {
bool output_enabled = (1 << i) & output_mask;
if (!output_enabled) {
continue;
}
ESCSettingsInterface *interface = nullptr;
switch (esc_type) {
case ESCType::AM32:
interface = new AM32Settings(i);
break;
default:
PX4_WARN("Unsupported ESC type for settings: %d", (int)esc_type);
break;
}
if (interface) {
_settings_handlers[i] = interface;
}
}
_settings_initialized = true;
}
int DShotTelemetry::parseCommandResponse()
{
if (hrt_elapsed_time(&_command_response_start) > 1_s) {
PX4_WARN("Command response timed out: %d bytes received", _command_response_position);
PX4_WARN("At time %.2fs", (double)hrt_absolute_time() / 1000000.);
_command_response_motor_index = -1;
_command_response_start = 0;
_command_response_position = 0;
return -1;
}
if (_uart.bytesAvailable() <= 0) {
return -1;
}
uint8_t buf[COMMAND_RESPONSE_MAX_SIZE] = {};
int bytes = _uart.read(buf, sizeof(buf));
// Handle potential overflow
if (_command_response_position + bytes >= COMMAND_RESPONSE_MAX_SIZE) {
_command_response_position = 0;
}
// Add bytes to buffer
for (int i = 0; i < bytes; i++) {
_command_response_buffer[_command_response_position++] = buf[i];
}
int index = -1;
switch (_command_response_command) {
case DSHOT_CMD_ESC_INFO: {
auto handler = _settings_handlers[_command_response_motor_index];
if (handler && _command_response_position == handler->getExpectedResponseSize()) {
if (handler->decodeInfoResponse(_command_response_buffer, _command_response_position)) {
index = _command_response_motor_index;
}
// Reset command state
_command_response_position = 0;
_command_response_start = 0;
_command_response_motor_index = -1;
}
break;
}
default:
break;
}
return index;
}
TelemetryStatus DShotTelemetry::parseTelemetryPacket(EscData *esc_data)
{
if (telemetryResponseFinished()) {
return TelemetryStatus::NotStarted;
}
// read from the uart. This must be non-blocking, so check first if there is data available
int bytes_available = _uart.bytesAvailable();
if (_uart.bytesAvailable() <= 0) {
if (hrt_elapsed_time(&_telemetry_request_start) > 30_ms) {
// NOTE: this happens when sending commands, there's a window after an ESC receives
// a command where it will not respond to any telemetry requests
// PX4_INFO("ESC telemetry timeout: %d", esc_data->motor_index);
++_num_timeouts;
if (bytes_available <= 0) {
// no data available. Check for a timeout
const hrt_abstime now = hrt_absolute_time();
if (_current_request_start > 0 && now - _current_request_start > 30_ms) {
if (_redirect_output) {
// clear and go back to internal buffer
_redirect_output = nullptr;
_current_motor_index_request = -1;
} else {
PX4_DEBUG("ESC telemetry timeout for motor %i (frame pos=%i)", _current_motor_index_request, _frame_position);
++_num_timeouts;
}
requestNextMotor(num_motors);
return -2;
// Mark telemetry request as finished
_telemetry_request_start = 0;
_frame_position = 0;
return TelemetryStatus::Timeout;
}
return -1;
return TelemetryStatus::NotReady;
}
uint8_t buf[ESC_FRAME_SIZE];
uint8_t buf[TELEMETRY_FRAME_SIZE];
int bytes = _uart.read(buf, sizeof(buf));
int ret = -1;
for (int i = 0; i < bytes && ret == -1; ++i) {
if (_redirect_output) {
_redirect_output->buffer[_redirect_output->buf_pos++] = buf[i];
if (_redirect_output->buf_pos == sizeof(_redirect_output->buffer)) {
// buffer full: return & go back to internal buffer
_redirect_output = nullptr;
ret = _current_motor_index_request;
_current_motor_index_request = -1;
requestNextMotor(num_motors);
}
} else {
bool successful_decoding;
if (decodeByte(buf[i], successful_decoding)) {
if (successful_decoding) {
ret = _current_motor_index_request;
}
requestNextMotor(num_motors);
}
}
}
return ret;
return decodeTelemetryResponse(buf, bytes, esc_data);
}
bool DShotTelemetry::decodeByte(uint8_t byte, bool &successful_decoding)
TelemetryStatus DShotTelemetry::decodeTelemetryResponse(uint8_t *buffer, int length, EscData *esc_data)
{
_frame_buffer[_frame_position++] = byte;
successful_decoding = false;
auto status = TelemetryStatus::NotReady;
if (_frame_position == ESC_FRAME_SIZE) {
PX4_DEBUG("got ESC frame for motor %i", _current_motor_index_request);
uint8_t checksum = crc8(_frame_buffer, ESC_FRAME_SIZE - 1);
uint8_t checksum_data = _frame_buffer[ESC_FRAME_SIZE - 1];
for (int i = 0; i < length; i++) {
_frame_buffer[_frame_position++] = buffer[i];
if (checksum == checksum_data) {
_latest_data.time = hrt_absolute_time();
_latest_data.temperature = _frame_buffer[0];
_latest_data.voltage = (_frame_buffer[1] << 8) | _frame_buffer[2];
_latest_data.current = (_frame_buffer[3] << 8) | _frame_buffer[4];
_latest_data.consumption = (_frame_buffer[5]) << 8 | _frame_buffer[6];
_latest_data.erpm = (_frame_buffer[7] << 8) | _frame_buffer[8];
PX4_DEBUG("Motor %i: temp=%i, V=%i, cur=%i, consumpt=%i, rpm=%i", _current_motor_index_request,
_latest_data.temperature, _latest_data.voltage, _latest_data.current, _latest_data.consumption,
_latest_data.erpm);
++_num_successful_responses;
successful_decoding = true;
/*
* ESC Telemetry Frame Structure (10 bytes total)
* =============================================
* Byte 0: Temperature (uint8_t) [deg C]
* Byte 1-2: Voltage (uint16_t, big-endian) [0.01V]
* Byte 3-4: Current (uint16_t, big-endian) [0.01A]
* Byte 5-6: Consumption (uint16_t, big-endian) [mAh]
* Byte 7-8: eRPM (uint16_t, big-endian) [100ERPM]
* Byte 9: CRC8 Checksum
*/
} else {
++_num_checksum_errors;
if (_frame_position == TELEMETRY_FRAME_SIZE) {
uint8_t checksum = crc8(_frame_buffer, TELEMETRY_FRAME_SIZE - 1);
uint8_t checksum_data = _frame_buffer[TELEMETRY_FRAME_SIZE - 1];
if (checksum == checksum_data) {
uint8_t temperature = _frame_buffer[0];
int16_t voltage = (_frame_buffer[1] << 8) | _frame_buffer[2];
int16_t current = (_frame_buffer[3] << 8) | _frame_buffer[4];
// int16_t consumption = (_frame_buffer[5]) << 8 | _frame_buffer[6];
int16_t erpm = (_frame_buffer[7] << 8) | _frame_buffer[8];
esc_data->timestamp = hrt_absolute_time();
esc_data->temperature = (float)temperature;
esc_data->voltage = (float)voltage * 0.01f;
esc_data->current = (float)current * 0.01f;
esc_data->erpm = erpm * 100;
++_num_successful_responses;
status = TelemetryStatus::Ready;
_uart.flush();
} else {
++_num_checksum_errors;
status = TelemetryStatus::ParseError;
}
// Mark telemetry request as finished
_telemetry_request_start = 0;
_frame_position = 0;
}
return true;
}
return false;
return status;
}
void DShotTelemetry::publish_esc_settings()
{
for (int i = 0; i < DSHOT_MAXIMUM_CHANNELS; i++) {
if (_settings_handlers[i]) {
_settings_handlers[i]->publish_latest();
}
}
}
void DShotTelemetry::setExpectCommandResponse(int motor_index, uint16_t command)
{
_command_response_motor_index = motor_index;
_command_response_command = command;
_command_response_start = hrt_absolute_time();
_command_response_position = 0;
}
bool DShotTelemetry::commandResponseFinished()
{
return _command_response_motor_index < 0;
}
bool DShotTelemetry::commandResponseStarted()
{
return _command_response_start > 0;
}
void DShotTelemetry::startTelemetryRequest()
{
_telemetry_request_start = hrt_absolute_time();
}
bool DShotTelemetry::telemetryResponseFinished()
{
return _telemetry_request_start == 0;
}
void DShotTelemetry::printStatus() const
{
PX4_INFO("Number of successful ESC frames: %i", _num_successful_responses);
PX4_INFO("Number of timeouts: %i", _num_timeouts);
PX4_INFO("Number of CRC errors: %i", _num_checksum_errors);
}
uint8_t DShotTelemetry::crc8(const uint8_t *buf, uint8_t len)
{
auto update_crc8 = [](uint8_t crc, uint8_t crc_seed) {
uint8_t crc_u = crc ^ crc_seed;
for (int i = 0; i < 8; ++i) {
crc_u = (crc_u & 0x80) ? 0x7 ^ (crc_u << 1) : (crc_u << 1);
}
return crc_u;
};
uint8_t crc = 0;
for (int i = 0; i < len; ++i) {
crc = update_crc8(buf[i], crc);
}
return crc;
}
void DShotTelemetry::requestNextMotor(int num_motors)
{
_current_motor_index_request = (_current_motor_index_request + 1) % num_motors;
_current_request_start = 0;
_frame_position = 0;
}
int DShotTelemetry::getRequestMotorIndex()
{
if (_current_request_start != 0) {
// already in progress, do not send another request
return -1;
}
_current_request_start = hrt_absolute_time();
return _current_motor_index_request;
}
void DShotTelemetry::decodeAndPrintEscInfoPacket(const OutputBuffer &buffer)
{
static constexpr int version_position = 12;
const uint8_t *data = buffer.buffer;
if (buffer.buf_pos < version_position) {
PX4_ERR("Not enough data received");
return;
}
enum class ESCVersionInfo {
BLHELI32,
KissV1,
KissV2,
};
ESCVersionInfo version;
int packet_length;
if (data[version_position] == 254) {
version = ESCVersionInfo::BLHELI32;
packet_length = esc_info_size_blheli32;
} else if (data[version_position] == 255) {
version = ESCVersionInfo::KissV2;
packet_length = esc_info_size_kiss_v2;
} else {
version = ESCVersionInfo::KissV1;
packet_length = esc_info_size_kiss_v1;
}
if (buffer.buf_pos != packet_length) {
PX4_ERR("Packet length mismatch (%i != %i)", buffer.buf_pos, packet_length);
return;
}
if (DShotTelemetry::crc8(data, packet_length - 1) != data[packet_length - 1]) {
PX4_ERR("Checksum mismatch");
return;
}
uint8_t esc_firmware_version = 0;
uint8_t esc_firmware_subversion = 0;
uint8_t esc_type = 0;
switch (version) {
case ESCVersionInfo::KissV1:
esc_firmware_version = data[12];
esc_firmware_subversion = (data[13] & 0x1f) + 97;
esc_type = (data[13] & 0xe0) >> 5;
break;
case ESCVersionInfo::KissV2:
case ESCVersionInfo::BLHELI32:
esc_firmware_version = data[13];
esc_firmware_subversion = data[14];
esc_type = data[15];
break;
}
const char *esc_type_str = "";
switch (version) {
case ESCVersionInfo::KissV1:
case ESCVersionInfo::KissV2:
switch (esc_type) {
case 1: esc_type_str = "KISS8A";
break;
case 2: esc_type_str = "KISS16A";
break;
case 3: esc_type_str = "KISS24A";
break;
case 5: esc_type_str = "KISS Ultralite";
break;
default: esc_type_str = "KISS (unknown)";
break;
}
break;
case ESCVersionInfo::BLHELI32: {
char *esc_type_mutable = (char *)(data + 31);
esc_type_mutable[32] = 0;
esc_type_str = esc_type_mutable;
}
break;
}
PX4_INFO("ESC Type: %s", esc_type_str);
PX4_INFO("MCU Serial Number: %02x%02x%02x-%02x%02x%02x-%02x%02x%02x-%02x%02x%02x",
data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7], data[8],
data[9], data[10], data[11]);
switch (version) {
case ESCVersionInfo::KissV1:
case ESCVersionInfo::KissV2:
PX4_INFO("Firmware version: %d.%d%c", esc_firmware_version / 100, esc_firmware_version % 100,
(char)esc_firmware_subversion);
break;
case ESCVersionInfo::BLHELI32:
PX4_INFO("Firmware version: %d.%d", esc_firmware_version, esc_firmware_subversion);
break;
}
if (version == ESCVersionInfo::KissV2 || version == ESCVersionInfo::BLHELI32) {
PX4_INFO("Rotation Direction: %s", data[16] ? "reversed" : "normal");
PX4_INFO("3D Mode: %s", data[17] ? "on" : "off");
}
if (version == ESCVersionInfo::BLHELI32) {
uint8_t setting = data[18];
switch (setting) {
case 0:
PX4_INFO("Low voltage Limit: off");
break;
case 255:
PX4_INFO("Low voltage Limit: unsupported");
break;
default:
PX4_INFO("Low voltage Limit: %d.%01d V", setting / 10, setting % 10);
break;
}
setting = data[19];
switch (setting) {
case 0:
PX4_INFO("Current Limit: off");
break;
case 255:
PX4_INFO("Current Limit: unsupported");
break;
default:
PX4_INFO("Current Limit: %d A", setting);
break;
}
for (int i = 0; i < 4; ++i) {
setting = data[i + 20];
PX4_INFO("LED %d: %s", i, setting ? (setting == 255 ? "unsupported" : "on") : "off");
}
}
PX4_INFO("Successful ESC frames: %i", _num_successful_responses);
PX4_INFO("Timeouts: %i", _num_timeouts);
PX4_INFO("CRC errors: %i", _num_checksum_errors);
}
+36 -66
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019 PX4 Development Team. All rights reserved.
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,90 +34,60 @@
#pragma once
#include <px4_platform_common/Serial.hpp>
#include <drivers/drv_hrt.h>
#include <uORB/Publication.hpp>
#include "DShotCommon.h"
#include "esc/AM32Settings.h"
class DShotTelemetry
{
public:
struct EscData {
hrt_abstime time;
int8_t temperature; ///< [deg C]
int16_t voltage; ///< [0.01V]
int16_t current; ///< [0.01A]
int16_t consumption; ///< [mAh]
int16_t erpm; ///< [100ERPM]
};
static constexpr int esc_info_size_blheli32 = 64;
static constexpr int esc_info_size_kiss_v1 = 15;
static constexpr int esc_info_size_kiss_v2 = 21;
static constexpr int max_esc_info_size = esc_info_size_blheli32;
struct OutputBuffer {
uint8_t buffer[max_esc_info_size];
int buf_pos{0};
int motor_index;
};
~DShotTelemetry();
int init(const char *uart_device, bool swap_rxtx);
/**
* Read telemetry from the UART (non-blocking) and handle timeouts.
* @param num_motors How many DShot enabled motors
* @return -1 if no update, -2 timeout, >= 0 for the motor index. Use @latestESCData() to get the data.
*/
int update(int num_motors);
bool redirectActive() const { return _redirect_output != nullptr; }
/**
* Get the motor index for which telemetry should be requested.
* @return -1 if no request should be made, motor index otherwise
*/
int getRequestMotorIndex();
const EscData &latestESCData() const { return _latest_data; }
/**
* Check whether we are currently expecting to read new data from an ESC
*/
bool expectingData() const { return _current_request_start != 0; }
void printStatus() const;
static void decodeAndPrintEscInfoPacket(const OutputBuffer &buffer);
void startTelemetryRequest();
bool telemetryResponseFinished();
TelemetryStatus parseTelemetryPacket(EscData *esc_data);
// Attempt to parse a command response. Returns the index of the ESC or -1 on failure.
int parseCommandResponse();
bool commandResponseFinished();
bool commandResponseStarted();
void setExpectCommandResponse(int motor_index, uint16_t command);
void initSettingsHandlers(ESCType esc_type, uint8_t output_mask);
void publish_esc_settings();
private:
static constexpr int ESC_FRAME_SIZE = 10;
static constexpr int COMMAND_RESPONSE_MAX_SIZE = 192;
static constexpr int TELEMETRY_FRAME_SIZE = 10;
TelemetryStatus decodeTelemetryResponse(uint8_t *buffer, int length, EscData *esc_data);
void requestNextMotor(int num_motors);
device::Serial _uart{};
/**
* Decode a single byte from an ESC feedback frame
* @param byte
* @param successful_decoding set to true if checksum matches
* @return true if received the expected amount of bytes and the next motor can be requested
*/
bool decodeByte(uint8_t byte, bool &successful_decoding);
// Command response
int _command_response_motor_index{-1};
uint16_t _command_response_command{0};
uint8_t _command_response_buffer[COMMAND_RESPONSE_MAX_SIZE];
int _command_response_position{0};
hrt_abstime _command_response_start{0};
static uint8_t crc8(const uint8_t *buf, uint8_t len);
device::Serial _uart {};
uint8_t _frame_buffer[ESC_FRAME_SIZE];
// Telemetry packet
EscData _latest_data{};
uint8_t _frame_buffer[TELEMETRY_FRAME_SIZE];
int _frame_position{0};
EscData _latest_data;
int _current_motor_index_request{-1};
hrt_abstime _current_request_start{0};
OutputBuffer *_redirect_output{nullptr}; ///< if set, all read bytes are stored here instead of the internal buffer
hrt_abstime _telemetry_request_start{0};
// statistics
int _num_timeouts{0};
int _num_successful_responses{0};
int _num_checksum_errors{0};
// Settings
ESCSettingsInterface *_settings_handlers[DSHOT_MAXIMUM_CHANNELS] = {nullptr};
ESCType _esc_type{ESCType::Unknown};
bool _settings_initialized{false};
};
+7
View File
@@ -3,3 +3,10 @@ menuconfig DRIVERS_DSHOT
default n
---help---
Enable support for dshot
config DSHOT_BITBANG
bool "Use bitbang DShot"
default n
depends on DRIVERS_DSHOT
---help---
Use bitbang GPIO DShot instead of DMA burst to timer registers
+86
View File
@@ -0,0 +1,86 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "AM32Settings.h"
#include "../DShotCommon.h"
#include <px4_platform_common/log.h>
static constexpr int RESPONSE_SIZE = EEPROM_SIZE + 1; // 48B data + 1B CRC
uORB::Publication<esc_eeprom_read_s> AM32Settings::_esc_eeprom_read_pub{ORB_ID(esc_eeprom_read)};
AM32Settings::AM32Settings(int index)
: _esc_index(index)
{}
int AM32Settings::getExpectedResponseSize()
{
return RESPONSE_SIZE;
}
void AM32Settings::publish_latest()
{
// PX4_INFO("publish_latest()");
esc_eeprom_read_s data = {};
data.timestamp = hrt_absolute_time();
data.firmware = 1; // ESC_FIRMWARE_AM32
data.index = _esc_index;
memcpy(data.data, &_eeprom_data, sizeof(_eeprom_data));
data.length = sizeof(_eeprom_data);
_esc_eeprom_read_pub.publish(data);
}
bool AM32Settings::decodeInfoResponse(const uint8_t *buf, int size)
{
if (size != RESPONSE_SIZE) {
return false;
}
uint8_t checksum = crc8(buf, EEPROM_SIZE);
uint8_t checksum_data = buf[EEPROM_SIZE];
if (checksum != checksum_data) {
PX4_WARN("Command Response checksum failed!");
return false;
}
PX4_INFO("Successfully received AM32 settings from ESC%d", _esc_index + 1);
// Store data for retrieval later if requested
memcpy(&_eeprom_data, buf, EEPROM_SIZE);
// Publish data immedietly
publish_latest();
return true;
}
+57
View File
@@ -0,0 +1,57 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "ESCSettingsInterface.h"
#include <uORB/Publication.hpp>
#include <uORB/topics/esc_eeprom_read.h>
static constexpr int EEPROM_SIZE = 48;
class AM32Settings : public ESCSettingsInterface
{
public:
AM32Settings(int index);
int getExpectedResponseSize() override;
bool decodeInfoResponse(const uint8_t *buf, int size) override;
void publish_latest() override;
private:
int _esc_index{};
uint8_t _eeprom_data[EEPROM_SIZE] {};
static uORB::Publication<esc_eeprom_read_s> _esc_eeprom_read_pub;
};
@@ -0,0 +1,52 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
enum class ESCType : uint8_t {
Unknown = 0,
AM32 = 1,
};
class ESCSettingsInterface
{
public:
virtual ~ESCSettingsInterface() = default;
virtual bool decodeInfoResponse(const uint8_t *buf, int size) = 0;
virtual int getExpectedResponseSize() = 0;
virtual void publish_latest() { /* no-op */};
// TODO: function to read data
// TODO: function to write data
};
+24 -11
View File
@@ -8,6 +8,15 @@ serial_config:
parameters:
- group: DShot
definitions:
DSHOT_ESC_TYPE:
description:
short: ESC Type
long: The ESC firmware type
type: enum
values:
0: Unknown
1: AM32
default: 0
DSHOT_MIN:
description:
short: Minimum DShot Motor Output
@@ -33,13 +42,13 @@ parameters:
When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent.
type: boolean
default: 0
DSHOT_BIDIR_EN:
DSHOT_BIDIR_EDT:
description:
short: Enable bidirectional DShot
short: Enable Extended DShot Telemetry
long: |
This parameter enables bidirectional DShot which provides RPM feedback.
Note that this requires ESCs that support bidirectional DSHot, e.g. BlHeli32.
This is not the same as DShot telemetry which requires an additional serial connection.
This parameter enables Extended DShot Telemetry which allows transmission of
additional telemetry within the eRPM frame. The EDT data is interleaved with
the eRPM frames at a low rate.
type: boolean
default: 0
reboot_required: true
@@ -63,14 +72,18 @@ parameters:
min: 0
max: 1000
default: 1000
MOT_POLE_COUNT: # only used by dshot so far, so keep it under the dshot group
DSHOT_MOT_POL${i}:
description:
short: Number of magnetic poles of the motors
short: Number of magnetic poles of motor ${i}
long: |
Specify the number of magnetic poles of the motors.
It is required to compute the RPM value from the eRPM returned with the ESC telemetry.
Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets).
Number of magnetic poles for motor ${i}.
Required to compute RPM from the eRPM returned by ESC telemetry.
Either get the number from the motor spec sheet or count the magnets
on the bell of the motor (not the stator magnets).
Typical motors for 5 inch props have 14 poles.
type: int32
default: 14
min: 2
max: 400
num_instances: 12
instance_start: 1
+3
View File
@@ -21,6 +21,9 @@ actuator_output:
type: enum
default: 400
values:
-8: BDShot150
-7: BDShot300
-6: BDShot600
-5: DShot150
-4: DShot300
-3: DShot600
+2
View File
@@ -141,6 +141,8 @@ public:
OutputFunction outputFunction(int index) const { return _function_assignment[index]; }
bool isMotor(int index) const { return isFunctionSet(index) && (_function_assignment[index] >= OutputFunction::Motor1) && (_function_assignment[index] <= OutputFunction::Motor12); }
/**
* Call this regularly from Run(). It will call interface.updateOutputs().
* @return true if outputs were updated
+2
View File
@@ -38,6 +38,7 @@
#include <px4_platform_common/log.h>
#include <px4_platform_common/px4_config.h>
#include <uORB/topics/uORBTopics.hpp>
#include <uORB/topics/esc_eeprom_read.h> // TODO: debugging
#include <string.h>
@@ -45,6 +46,7 @@ using namespace px4::logger;
void LoggedTopics::add_default_topics()
{
add_topic("esc_eeprom_read"); // TODO: debugging
add_topic("action_request");
add_topic("actuator_armed");
add_optional_topic("actuator_controls_status_0", 300);
+15
View File
@@ -1431,6 +1431,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("EFI_STATUS", 2.0f);
configure_stream_local("ESC_INFO", 1.0f);
configure_stream_local("ESC_STATUS", 1.0f);
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
configure_stream_local("ESC_EEPROM", unlimited_rate);
#endif
configure_stream_local("ESTIMATOR_STATUS", 0.5f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 5.0f);
@@ -1497,6 +1500,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("DISTANCE_SENSOR", 10.0f);
configure_stream_local("ESC_INFO", 10.0f);
configure_stream_local("ESC_STATUS", 10.0f);
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
configure_stream_local("ESC_EEPROM", unlimited_rate);
#endif
configure_stream_local("MOUNT_ORIENTATION", 10.0f);
configure_stream_local("OBSTACLE_DISTANCE", 10.0f);
configure_stream_local("ODOMETRY", 30.0f);
@@ -1675,6 +1681,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("EFI_STATUS", 10.0f);
configure_stream_local("ESC_INFO", 10.0f);
configure_stream_local("ESC_STATUS", 10.0f);
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
configure_stream_local("ESC_EEPROM", unlimited_rate);
#endif
configure_stream_local("ESTIMATOR_STATUS", 5.0f);
configure_stream_local("EXTENDED_SYS_STATE", 2.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
@@ -1770,6 +1779,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("ESC_INFO", 1.0f);
configure_stream_local("ESC_STATUS", 5.0f);
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
configure_stream_local("ESC_EEPROM", unlimited_rate);
#endif
configure_stream_local("ADSB_VEHICLE", unlimited_rate);
configure_stream_local("ATTITUDE_TARGET", 2.0f);
@@ -1838,6 +1850,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 2.0f);
configure_stream_local("ESC_INFO", 1.0f);
configure_stream_local("ESC_STATUS", 2.0f);
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
configure_stream_local("ESC_EEPROM", unlimited_rate);
#endif
configure_stream_local("ADSB_VEHICLE", 1.0f);
configure_stream_local("ATTITUDE_TARGET", 0.5f);
configure_stream_local("AVAILABLE_MODES", 0.3f);
+7
View File
@@ -137,6 +137,10 @@
#include "streams/CURRENT_MODE.hpp"
#endif
#ifdef MAVLINK_MSG_ID_ESC_EEPROM // Only defined if development.xml is used
#include "streams/ESC_EEPROM.hpp"
#endif
#if !defined(CONSTRAINED_FLASH)
# include "streams/ADSB_VEHICLE.hpp"
# include "streams/AUTOPILOT_STATE_FOR_GIMBAL_DEVICE.hpp"
@@ -468,6 +472,9 @@ static const StreamListItem streams_list[] = {
#if defined(ESC_STATUS_HPP)
create_stream_list_item<MavlinkStreamESCStatus>(),
#endif // ESC_STATUS_HPP
#if defined(ESC_EEPROM_HPP)
create_stream_list_item<MavlinkStreamEscEeprom>(),
#endif // ESC_EEPROM_HPP
#if defined(AUTOPILOT_VERSION_HPP)
create_stream_list_item<MavlinkStreamAutopilotVersion>(),
#endif // AUTOPILOT_VERSION_HPP
+61 -7
View File
@@ -329,6 +329,14 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
case MAVLINK_MSG_ID_SET_VELOCITY_LIMITS:
handle_message_set_velocity_limits(msg);
break;
#endif
#if defined(MAVLINK_MSG_ID_ESC_EEPROM) // For now only defined if development.xml is used
case MAVLINK_MSG_ID_ESC_EEPROM:
handle_message_esc_eeprom(msg);
break;
#endif
default:
@@ -594,14 +602,23 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
uint16_t message_id = (uint16_t)roundf(vehicle_command.param1);
if (message_id == MAVLINK_MSG_ID_MESSAGE_INTERVAL) {
get_message_interval((int)(cmd_mavlink.param2 + 0.5f));
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
} else {
result = handle_request_message_command(message_id,
vehicle_command.param2, vehicle_command.param3, vehicle_command.param4,
vehicle_command.param5, vehicle_command.param6, vehicle_command.param7);
}
// NOTE: ESC_EEPROM message request handling is deferred - DShot driver handles and triggers reading
if (message_id == MAVLINK_MSG_ID_ESC_EEPROM) {
PX4_INFO("publishing MAV_CMD_REQUEST_MESSAGE for MAVLINK_MSG_ID_ESC_EEPROM");
_cmd_pub.publish(vehicle_command);
} else
#endif
if (message_id == MAVLINK_MSG_ID_MESSAGE_INTERVAL) {
get_message_interval((int)(cmd_mavlink.param2 + 0.5f));
} else {
result = handle_request_message_command(message_id,
vehicle_command.param2, vehicle_command.param3, vehicle_command.param4,
vehicle_command.param5, vehicle_command.param6, vehicle_command.param7);
}
} else if (cmd_mavlink.command == MAV_CMD_INJECT_FAILURE) {
if (_mavlink.failure_injection_enabled()) {
@@ -1304,6 +1321,43 @@ void MavlinkReceiver::handle_message_set_velocity_limits(mavlink_message_t *msg)
}
#endif // MAVLINK_MSG_ID_SET_VELOCITY_LIMITS
#if defined(MAVLINK_MSG_ID_ESC_EEPROM) // For now only defined if development.xml is used
void
MavlinkReceiver::handle_message_esc_eeprom(mavlink_message_t *msg)
{
mavlink_esc_eeprom_t message;
mavlink_msg_esc_eeprom_decode(msg, &message);
esc_eeprom_write_s eeprom{};
eeprom.timestamp = hrt_absolute_time();
eeprom.firmware = message.firmware;
eeprom.index = message.esc_index;
uint8_t min_length = sizeof(eeprom.data);
int length = message.length;
if (length > min_length) {
length = min_length;
}
for (int i = 0; i < length && i < min_length; i++) {
int mask_index = i / 32; // Which uint32_t in the write_mask array
int bit_index = i % 32; // Which bit within that uint32_t
if (message.write_mask[mask_index] & (1U << bit_index)) {
eeprom.data[i] = message.data[i];
}
}
eeprom.length = length;
memcpy(eeprom.write_mask, message.write_mask, sizeof(eeprom.write_mask));
PX4_INFO("ESC EEPROM write request for ESC%d", eeprom.index + 1);
_esc_eeprom_write_pub.publish(eeprom);
}
#endif // MAVLINK_MSG_ID_ESC_EEPROM
void
MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
{
+5
View File
@@ -64,6 +64,7 @@
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/autotune_attitude_control_status.h>
#include <uORB/topics/esc_eeprom_write.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/camera_status.h>
#include <uORB/topics/cellular_status.h>
@@ -202,6 +203,9 @@ private:
void handle_message_utm_global_position(mavlink_message_t *msg);
#if defined(MAVLINK_MSG_ID_SET_VELOCITY_LIMITS) // For now only defined if development.xml is used
void handle_message_set_velocity_limits(mavlink_message_t *msg);
#endif
#if defined(MAVLINK_MSG_ID_ESC_EEPROM) // For now only defined if development.xml is used
void handle_message_esc_eeprom(mavlink_message_t *msg);
#endif
void handle_message_vision_position_estimate(mavlink_message_t *msg);
void handle_message_gimbal_manager_set_attitude(mavlink_message_t *msg);
@@ -329,6 +333,7 @@ private:
uORB::Publication<vehicle_odometry_s> _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)};
uORB::Publication<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
uORB::Publication<vehicle_rates_setpoint_s> _rates_sp_pub{ORB_ID(vehicle_rates_setpoint)};
uORB::Publication<esc_eeprom_write_s> _esc_eeprom_write_pub{ORB_ID(esc_eeprom_write)};
#if !defined(CONSTRAINED_FLASH)
uORB::Publication<debug_array_s> _debug_array_pub {ORB_ID(debug_array)};
@@ -0,0 +1,93 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef ESC_EEPROM_HPP
#define ESC_EEPROM_HPP
#include <uORB/topics/esc_eeprom_read.h>
class MavlinkStreamEscEeprom : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamEscEeprom(mavlink); }
static constexpr const char *get_name_static() { return "ESC_EEPROM"; }
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_ESC_EEPROM; }
const char *get_name() const override { return get_name_static(); }
uint16_t get_id() override { return get_id_static(); }
unsigned get_size() override
{
return _esc_eeprom_read_sub.advertised() ? MAVLINK_MSG_ID_ESC_EEPROM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
}
private:
explicit MavlinkStreamEscEeprom(Mavlink *mavlink) : MavlinkStream(mavlink) {}
uORB::Subscription _esc_eeprom_read_sub{ORB_ID(esc_eeprom_read)};
bool emit_message(bool force)
{
esc_eeprom_read_s eeprom = {};
if (_esc_eeprom_read_sub.update(&eeprom) || force) {
mavlink_esc_eeprom_t msg = {};
msg.firmware = eeprom.firmware;
msg.esc_index = eeprom.index;
msg.msg_index = 0;
msg.msg_count = 1;
memcpy(msg.data, eeprom.data, sizeof(eeprom.data));
msg.length = eeprom.length;
mavlink_msg_esc_eeprom_send_struct(_mavlink->get_channel(), &msg);
return true;
}
return false;
}
bool request_message(float param2, float param3, float param4, float param5, float param6, float param7) override
{
return emit_message(true);
}
bool send() override
{
return emit_message(false);
}
};
#endif // ESC_EEPROM_HPP
+10 -7
View File
@@ -70,7 +70,7 @@ private:
uint16_t counter;
uint8_t esc_count;
uint8_t esc_connectiontype;
uint8_t esc_online_flags;
uint16_t esc_online_flags;
};
struct EscInfo {
@@ -98,7 +98,7 @@ private:
_interface[i].esc_connectiontype = esc.esc_connectiontype;
// Capture online_flags, we will map from index to motor number
uint8_t online_flags = esc.esc_online_flags;
uint16_t online_flags = esc.esc_online_flags;
_interface[i].esc_online_flags = 0;
for (int j = 0; j < esc_status_s::CONNECTED_ESC_MAX; j++) {
@@ -108,11 +108,14 @@ private:
if (is_motor) {
// Map OutputFunction number to index
int index = (int)esc.esc[j].actuator_function - esc_report_s::ACTUATOR_FUNCTION_MOTOR1;
_escs[index].online = online_flags & (1 << j);
_escs[index].failure_flags = esc.esc[j].failures;
_escs[index].error_count = esc.esc[j].esc_errorcount;
_escs[index].timestamp = esc.esc[j].timestamp;
_escs[index].temperature = esc.esc[j].esc_temperature * 100.f;
if (index >= 0 && index < MAX_ESC_OUTPUTS) {
_escs[index].online = online_flags & (1 << j);
_escs[index].failure_flags = esc.esc[j].failures;
_escs[index].error_count = esc.esc[j].esc_errorcount;
_escs[index].timestamp = esc.esc[j].timestamp;
_escs[index].temperature = esc.esc[j].esc_temperature * 100.f;
}
}
}
}
+7 -4
View File
@@ -90,10 +90,13 @@ private:
if (is_motor) {
// Map OutputFunction number to index
int index = (int)esc.esc[j].actuator_function - esc_report_s::ACTUATOR_FUNCTION_MOTOR1;
_escs[index].timestamp = esc.esc[j].timestamp;
_escs[index].rpm = esc.esc[j].esc_rpm;
_escs[index].voltage = esc.esc[j].esc_voltage;
_escs[index].current = esc.esc[j].esc_current;
if (index >= 0 && index < MAX_ESC_OUTPUTS) {
_escs[index].timestamp = esc.esc[j].timestamp;
_escs[index].rpm = esc.esc[j].esc_rpm;
_escs[index].voltage = esc.esc[j].esc_voltage;
_escs[index].current = esc.esc[j].esc_current;
}
}
}
}