mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-14 19:00:05 +08:00
Compare commits
98 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| a3bb0d5b0a | |||
| 85dfa8c8b6 | |||
| 789bdbd346 | |||
| e5068e1f1d | |||
| f78ce5b227 | |||
| 4cfda1feed | |||
| ae5b191c42 | |||
| 77d8e4f213 | |||
| ecf8191aad | |||
| 3fb1459c33 | |||
| ee196fadb8 | |||
| fd9abf76fd | |||
| a98d68f919 | |||
| 7d2d85e6ac | |||
| 34845a62b0 | |||
| 7715a4ab4c | |||
| ea2ca45cf9 | |||
| 14864814ef | |||
| 3a6a57bd45 | |||
| e0af9f4ef4 | |||
| 0294d4a794 | |||
| d411e1c40d | |||
| 833e4536b7 | |||
| 1b7e12cf90 | |||
| aacb7e35dd | |||
| 1dbee4100a | |||
| dbb00d500f | |||
| 61a8ae80a6 | |||
| f8329ff80d | |||
| b4b1b44c6a | |||
| f5a56ae42f | |||
| c4535683a7 | |||
| f9cdd095b8 | |||
| 61c990c5ee | |||
| 8115cf2597 | |||
| 7e2361a592 | |||
| 7b0984584f | |||
| b9f6e35a43 | |||
| f6a0ed57a4 | |||
| 408a77376f | |||
| b1b3a695e7 | |||
| 53a4a871ef | |||
| 81a8a88db7 | |||
| 130ec776b2 | |||
| b05c772ee3 | |||
| 4f70ed367e | |||
| a9f5e5d70f | |||
| ac5fba4c28 | |||
| 6f8ba007d1 | |||
| 47bb1437e4 | |||
| b26b3ac29d | |||
| 3ef8b10987 | |||
| 0c51b25391 | |||
| d72542a48d | |||
| 5cde03652a | |||
| bbbac3bb16 | |||
| c9a8f37fef | |||
| 44f62fd764 | |||
| 89f14100ab | |||
| b1585a7f55 | |||
| e835394d25 | |||
| 4d09521d98 | |||
| 8847c3cc83 | |||
| 7edc606296 | |||
| 6bc0e0c74e | |||
| 9ad690dc85 | |||
| c434ef1507 | |||
| 458c775bfd | |||
| 24d7cd48e5 | |||
| b5e9457ba2 | |||
| 597611e7a5 | |||
| 2d7b3a83c3 | |||
| 72cd09bd87 | |||
| 4ee3d2778e | |||
| bf783779b6 | |||
| 8ab112b4c3 | |||
| 3c8a652538 | |||
| f6eeacfd8b | |||
| 22587b09e5 | |||
| 4b3cd1e9a2 | |||
| d1d54178d9 | |||
| 46cecf61c5 | |||
| 3b9ea305f7 | |||
| c6c8cdd78f | |||
| e6744590cf | |||
| 22ac08547e | |||
| b4e69e95fa | |||
| 55cdb4d192 | |||
| 5c7e33d2cb | |||
| bd4ac2a11b | |||
| 1d576c074b | |||
| 9761cb3d6f | |||
| bc89140345 | |||
| 316c0c187a | |||
| a63f1809ff | |||
| 844b5adab2 | |||
| 74da73e37d | |||
| b93cb96c4f |
@@ -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`
|
||||
Executable
+433
@@ -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()
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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.
@@ -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
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -0,0 +1,3 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROMFSROOT=""
|
||||
@@ -0,0 +1,86 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROOT_PATH="/fs/flash"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS1"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y
|
||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
# CONFIG_EKF2_AUX_GLOBAL_POSITION is not set
|
||||
# CONFIG_EKF2_AUXVEL is not set
|
||||
# CONFIG_EKF2_BARO_COMPENSATION is not set
|
||||
# CONFIG_EKF2_DRAG_FUSION is not set
|
||||
# CONFIG_EKF2_GNSS_YAW is not set
|
||||
# CONFIG_EKF2_SIDESLIP is not set
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_GPIO=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
Binary file not shown.
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 1209,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the AirBrainH743 by Gear Up",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "AirBrainH743",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1966080,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,17 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# AirBrainH743 board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Battery voltage divider and current scale
|
||||
param set-default BAT1_V_DIV 15.0
|
||||
param set-default BAT1_A_PER_V 101.0
|
||||
|
||||
# system_power unavailable
|
||||
param set-default CBRK_SUPPLY_CHK 894281
|
||||
|
||||
param set-default IMU_GYRO_RATEMAX 2000
|
||||
|
||||
# W25N NAND flash with littlefs (128 MB): larger buffer, auto-rotate
|
||||
set LOGGER_BUF 32
|
||||
param set-default SDLOG_DIRS_MAX 3
|
||||
@@ -0,0 +1,6 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# AirBrainH743 specific board extras init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# No extras configured by default
|
||||
@@ -0,0 +1,16 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# AirBrainH743 specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
board_adc start
|
||||
|
||||
# Internal SPI bus IMU - ICM42688P (Invensensev3)
|
||||
icm42688p -R 2 -b 1 -s start
|
||||
|
||||
# Internal I2C bus barometer - DPS310 @ 0x76 (118 decimal)
|
||||
dps310 -I -a 118 start
|
||||
|
||||
# Internal I2C bus magnetometer - LIS2MDL @ 0x1E (30 decimal)
|
||||
# Using iis2mdc driver (functionally equivalent to LIS2MDL)
|
||||
iis2mdc -I -R 2 -a 30 start
|
||||
@@ -0,0 +1,3 @@
|
||||
#
|
||||
# Board-specific Kconfig for AirBrainH743
|
||||
#
|
||||
@@ -0,0 +1,89 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DEV_CONSOLE is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_SPI_EXCHANGE is not set
|
||||
# CONFIG_STM32H7_SYSCFG is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/gearup/airbrainh743/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743VI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254
|
||||
CONFIG_BOARD_LATE_INITIALIZE=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004b
|
||||
CONFIG_CDCACM_PRODUCTSTR="AirBrainH743 BL"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3162
|
||||
CONFIG_CDCACM_VENDORSTR="Gear Up"
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FDCLONE_DISABLE=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="bootloader_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SPI=y
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_SYSTEMTICK_HOOK=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGINT_CHAR=0x03
|
||||
CONFIG_TTY_SIGTSTP=y
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
@@ -0,0 +1,346 @@
|
||||
/************************************************************************************
|
||||
* nuttx-config/include/board.h
|
||||
*
|
||||
* 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 NuttX 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 __NUTTX_CONFIG_AIRBRAINH743_INCLUDE_BOARD_H
|
||||
#define __NUTTX_CONFIG_AIRBRAINH743_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The AirBrainH743 board provides the following clock sources:
|
||||
*
|
||||
* X1: 8 MHz crystal for HSE
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 8000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE = 8,000,000
|
||||
*
|
||||
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
*
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* CPUCLK = SYSCLK / D1CPRE
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_USEHSE
|
||||
|
||||
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
|
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
*
|
||||
* PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
|
||||
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
|
||||
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
|
||||
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVP1EN | \
|
||||
RCC_PLLCFGR_DIVQ1EN | \
|
||||
RCC_PLLCFGR_DIVR1EN)
|
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120)
|
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(5)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
|
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120)
|
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 5)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
|
||||
|
||||
/* PLL2 */
|
||||
|
||||
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
|
||||
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVP2EN | \
|
||||
RCC_PLLCFGR_DIVQ2EN | \
|
||||
RCC_PLLCFGR_DIVR2EN)
|
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2)
|
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
|
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
|
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
|
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
|
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48)
|
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
|
||||
/* PLL3 */
|
||||
|
||||
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
|
||||
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVQ3EN)
|
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2)
|
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
|
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
|
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
|
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
|
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48)
|
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
|
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
|
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
|
||||
|
||||
/* SYSCLK = PLL1P = 480MHz
|
||||
* CPUCLK = SYSCLK / 1 = 480 MHz
|
||||
*/
|
||||
|
||||
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
|
||||
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
|
||||
|
||||
/* Configure Clock Assignments */
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240
|
||||
*/
|
||||
|
||||
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
|
||||
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
|
||||
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */
|
||||
|
||||
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
|
||||
|
||||
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
|
||||
|
||||
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
|
||||
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB4 clock (PCLK4) is HCLK/2 (120 MHz) */
|
||||
|
||||
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
|
||||
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timer clock frequencies */
|
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 */
|
||||
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* Timers driven from APB2 will be twice PCLK2 */
|
||||
|
||||
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Kernel Clock Configuration */
|
||||
|
||||
/* I2C123 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
|
||||
|
||||
/* I2C4 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
|
||||
|
||||
/* SPI123 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
|
||||
|
||||
/* SPI45 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2
|
||||
|
||||
/* SPI6 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2
|
||||
|
||||
/* USB 1 and 2 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
|
||||
|
||||
/* ADC 1 2 3 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2
|
||||
|
||||
/* FDCAN 1 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE
|
||||
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
|
||||
|
||||
/* FLASH wait states */
|
||||
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_LED3 2
|
||||
#define BOARD_NLEDS 3
|
||||
|
||||
#define BOARD_LED_RED BOARD_LED1
|
||||
#define BOARD_LED_GREEN BOARD_LED2
|
||||
#define BOARD_LED_BLUE BOARD_LED3
|
||||
|
||||
/* LED bits for use with board_userled_all() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3)
|
||||
|
||||
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
|
||||
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
|
||||
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
|
||||
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
|
||||
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
|
||||
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
|
||||
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
|
||||
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
|
||||
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/* USART1 - Debug (PA9 TX, PA10 RX) */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
|
||||
|
||||
/* USART2 - RC input (PD5 TX, PD6 RX) */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
|
||||
/* USART3 - DJI/MSP (PD8 TX, PD9 RX) */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
|
||||
/* UART4 - General (PB9 TX, PB8 RX) */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_3 /* PB8 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */
|
||||
|
||||
/* UART5 - Companion (PB13 TX, PB12 RX) */
|
||||
#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */
|
||||
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
|
||||
|
||||
/* UART7 - ESC telemetry (PE8 TX, PE7 RX) */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
|
||||
/* UART8 - GPS (PE1 TX, PE0 RX) */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
|
||||
|
||||
/* SPI
|
||||
*
|
||||
* SPI1: IMU (PA5 SCK, PA6 MISO, PA7 MOSI)
|
||||
* SPI2: W25N Flash (PD3 SCK, PB14 MISO, PC3 MOSI)
|
||||
* SPI4: External (PE12 SCK, PE5 MISO, PE6 MOSI)
|
||||
*/
|
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */
|
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PD3 */
|
||||
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE12 */
|
||||
|
||||
/* I2C
|
||||
*
|
||||
* I2C1: Internal (PB6 SCL, PB7 SDA)
|
||||
* I2C4: External (PD12 SCL, PD13 SDA)
|
||||
*/
|
||||
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
|
||||
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 /* PD12 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 /* PD13 */
|
||||
|
||||
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN12)
|
||||
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN13)
|
||||
|
||||
|
||||
/* USB
|
||||
*
|
||||
* OTG_FS_DM PA11
|
||||
* OTG_FS_DP PA12
|
||||
* VBUS PD0
|
||||
*/
|
||||
|
||||
|
||||
#endif /*__NUTTX_CONFIG_AIRBRAINH743_INCLUDE_BOARD_H */
|
||||
@@ -0,0 +1,42 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/* DMA mapping for SPI1 (IMU) */
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
|
||||
|
||||
/* DMA mapping for SPI2 (W25N Flash) */
|
||||
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
|
||||
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
|
||||
@@ -0,0 +1,258 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_DISABLE_PTHREAD is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_CAT is not set
|
||||
# CONFIG_NSH_DISABLE_CD is not set
|
||||
# CONFIG_NSH_DISABLE_CP is not set
|
||||
# CONFIG_NSH_DISABLE_DATE is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_ECHO is not set
|
||||
# CONFIG_NSH_DISABLE_ENV is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_EXPORT is not set
|
||||
# CONFIG_NSH_DISABLE_FREE is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_HELP is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_KILL is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PRINTF is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
|
||||
# CONFIG_NSH_DISABLE_PWD is not set
|
||||
# CONFIG_NSH_DISABLE_RM is not set
|
||||
# CONFIG_NSH_DISABLE_RMDIR is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_SET is not set
|
||||
# CONFIG_NSH_DISABLE_SLEEP is not set
|
||||
# CONFIG_NSH_DISABLE_SOURCE is not set
|
||||
# CONFIG_NSH_DISABLE_TEST is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_NSH_DISABLE_UMOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_UNSET is not set
|
||||
# CONFIG_NSH_DISABLE_USLEEP is not set
|
||||
# CONFIG_SPI_CALLBACK is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/gearup/airbrainh743/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743VI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0050
|
||||
CONFIG_CDCACM_PRODUCTSTR="AirBrainH743"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3162
|
||||
CONFIG_CDCACM_VENDORSTR="Gear Up"
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_FS_LITTLEFS=y
|
||||
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
|
||||
CONFIG_FS_LITTLEFS_READ_SIZE_FACTOR=1
|
||||
CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=1
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=4
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_W25N=y
|
||||
CONFIG_W25N_SPIFREQUENCY=104000000
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_OTG_ID_GPIO_DISABLE=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_ADC3=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BDMA=y
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DMAMUX1=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI2_DMA=y
|
||||
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
|
||||
CONFIG_STM32H7_SPI4=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM2=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_TIM5=y
|
||||
CONFIG_STM32H7_TIM8=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART5=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGTSTP=y
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART5_BAUD=57600
|
||||
CONFIG_UART5_RXBUFSIZE=600
|
||||
CONFIG_UART5_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_TXBUFSIZE=1500
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_SERIAL_CONSOLE=y
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,213 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory.
|
||||
* The flash memory is partitioned into a User Flash memory and a System
|
||||
* Flash memory. Each of these memories has two banks:
|
||||
*
|
||||
* 1) User Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
|
||||
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
|
||||
*
|
||||
* 2) System Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
|
||||
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
|
||||
*
|
||||
* 3) User option bytes for user configuration, only in Bank 1.
|
||||
*
|
||||
* In the STM32H743II, two different boot spaces can be selected through
|
||||
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
|
||||
* BOOT_ADD1 option bytes:
|
||||
*
|
||||
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
|
||||
* ST programmed value: Flash memory at 0x0800:0000
|
||||
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
|
||||
* ST programmed value: System bootloader at 0x1FF0:0000
|
||||
*
|
||||
* The Durandal has a Switch on board, the BOOT0 pin is at ground so by default,
|
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is
|
||||
* drepresed, then the boot will be from 0x1FF0:0000
|
||||
*
|
||||
* The STM32H743ZI also has 1024Kb of data SRAM.
|
||||
* SRAM is split up into several blocks and into three power domains:
|
||||
*
|
||||
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
|
||||
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
|
||||
*
|
||||
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
|
||||
*
|
||||
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
|
||||
* DTCM ports. The DTCM-RAM could be used for critical real-time
|
||||
* data, such as interrupt service routines or stack / heap memory.
|
||||
* Both DTCM-RAMs can be used in parallel (for load/store operations)
|
||||
* thanks to the Cortex-M7 dual issue capability.
|
||||
*
|
||||
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
|
||||
*
|
||||
* This RAM is connected to ITCM 64-bit interface designed for
|
||||
* execution of critical real-times routines by the CPU.
|
||||
*
|
||||
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
|
||||
* through D1 domain AXI bus matrix
|
||||
*
|
||||
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
|
||||
*
|
||||
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
|
||||
* through D2 domain AHB bus matrix
|
||||
*
|
||||
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
|
||||
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
|
||||
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
|
||||
*
|
||||
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
|
||||
*
|
||||
* 4) AHB SRAM (D3 domain) accessible by most of system masters
|
||||
* through D3 domain AHB bus matrix
|
||||
*
|
||||
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
|
||||
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K
|
||||
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
|
||||
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
|
||||
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
|
||||
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
|
||||
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
|
||||
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
EXTERN(_vectors)
|
||||
ENTRY(_stext)
|
||||
|
||||
/*
|
||||
* Ensure that abort() is present in the final object. The exception handling
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > flash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,228 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The board uses an STM32H743II and has 2048Kb of main FLASH memory.
|
||||
* The flash memory is partitioned into a User Flash memory and a System
|
||||
* Flash memory. Each of these memories has two banks:
|
||||
*
|
||||
* 1) User Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
|
||||
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
|
||||
*
|
||||
* 2) System Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
|
||||
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
|
||||
*
|
||||
* 3) User option bytes for user configuration, only in Bank 1.
|
||||
*
|
||||
* In the STM32H743II, two different boot spaces can be selected through
|
||||
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
|
||||
* BOOT_ADD1 option bytes:
|
||||
*
|
||||
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
|
||||
* ST programmed value: Flash memory at 0x0800:0000
|
||||
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
|
||||
* ST programmed value: System bootloader at 0x1FF0:0000
|
||||
*
|
||||
* There's a switch on board, the BOOT0 pin is at ground so by default,
|
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is
|
||||
* drepresed, then the boot will be from 0x1FF0:0000
|
||||
*
|
||||
* The STM32H743ZI also has 1024Kb of data SRAM.
|
||||
* SRAM is split up into several blocks and into three power domains:
|
||||
*
|
||||
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
|
||||
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
|
||||
*
|
||||
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
|
||||
*
|
||||
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
|
||||
* DTCM ports. The DTCM-RAM could be used for critical real-time
|
||||
* data, such as interrupt service routines or stack / heap memory.
|
||||
* Both DTCM-RAMs can be used in parallel (for load/store operations)
|
||||
* thanks to the Cortex-M7 dual issue capability.
|
||||
*
|
||||
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
|
||||
*
|
||||
* This RAM is connected to ITCM 64-bit interface designed for
|
||||
* execution of critical real-times routines by the CPU.
|
||||
*
|
||||
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
|
||||
* through D1 domain AXI bus matrix
|
||||
*
|
||||
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
|
||||
*
|
||||
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
|
||||
* through D2 domain AHB bus matrix
|
||||
*
|
||||
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
|
||||
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
|
||||
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
|
||||
*
|
||||
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
|
||||
*
|
||||
* 4) AHB SRAM (D3 domain) accessible by most of system masters
|
||||
* through D3 domain AHB bus matrix
|
||||
*
|
||||
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
|
||||
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
|
||||
|
||||
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
|
||||
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
|
||||
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
|
||||
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
EXTERN(_vectors)
|
||||
ENTRY(_stext)
|
||||
|
||||
/*
|
||||
* Ensure that abort() is present in the final object. The exception handling
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
|
||||
} > FLASH
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > FLASH
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > FLASH
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
|
||||
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
|
||||
. = ALIGN(16);
|
||||
FILL(0xffff)
|
||||
. += 16;
|
||||
} > AXI_SRAM AT > FLASH = 0xffff
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_SRAM
|
||||
|
||||
/* Emit the the D3 power domain section for locating BDMA data */
|
||||
|
||||
.sram4_reserve (NOLOAD) :
|
||||
{
|
||||
*(.sram4)
|
||||
. = ALIGN(4);
|
||||
_sram4_heap_start = ABSOLUTE(.);
|
||||
} > SRAM4
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,67 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
add_library(drivers_board
|
||||
bootloader_main.c
|
||||
usb.c
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
bootloader
|
||||
)
|
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
|
||||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
add_dependencies(drivers_board arch_board_hw_info)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_io_pins
|
||||
arch_spi
|
||||
arch_board_hw_info
|
||||
drivers__led
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
px4_layer
|
||||
)
|
||||
endif()
|
||||
@@ -0,0 +1,223 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* AirBrainH743 (Gear Up) internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* Enable small flash logging support (for W25N NAND flash) */
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
# define BOARD_SMALL_FLASH_LOGGING 1
|
||||
#endif
|
||||
|
||||
/* LEDs are active low
|
||||
* STAT RGB LED:
|
||||
* PB15 = Blue
|
||||
* PD11 = Green
|
||||
* PD15 = Red
|
||||
* BAT LED (orange): hardwired to power input
|
||||
*/
|
||||
#define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
|
||||
#define GPIO_nLED_GREEN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
|
||||
#define GPIO_nLED_RED /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN15)
|
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
#define BOARD_OVERLOAD_LED LED_RED
|
||||
#define BOARD_ARMED_STATE_LED LED_GREEN
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that
|
||||
* can be used by the Px4 Firmware in the adc driver
|
||||
*/
|
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */
|
||||
#define ADC1_CH(n) (n)
|
||||
|
||||
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PC4 */ GPIO_ADC12_INP4, \
|
||||
/* PC5 */ GPIO_ADC12_INP8
|
||||
|
||||
/* Define Channel numbers must match above GPIO pin IN(n)*/
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC4 */ ADC1_CH(4)
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL /* PC5 */ ADC1_CH(8)
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL))
|
||||
|
||||
|
||||
/* Define Battery Voltage Divider and A per V
|
||||
*/
|
||||
#define BOARD_BATTERY1_V_DIV (15.0f)
|
||||
#define BOARD_BATTERY1_A_PER_V (101.0f)
|
||||
|
||||
|
||||
/* PWM
|
||||
* 8 PWM outputs for motors + 1 for LED strip
|
||||
*/
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 9
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 9
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
|
||||
/* Tone alarm output (directly connected to transistor switch of external buzzer)
|
||||
*
|
||||
* GPIO mode only (active buzzer) - passive buzzer with different tones is not
|
||||
* supported because PA15 can only use TIM2, which is also used for motor outputs
|
||||
* M7 (PB10, TIM2_CH3) and M8 (PB11, TIM2_CH4). The PWM tone alarm driver changes
|
||||
* the timer's prescaler and auto-reload registers (shared across all channels),
|
||||
* which would affect M7/M8 PWM frequency during tone playback.
|
||||
*/
|
||||
#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
|
||||
/* ICM42688P FSYNC - directly connected to IMU via GPIO (no timer).
|
||||
* The driver clears TMST_FSYNC_EN and FIFO_TMST_FSYNC_EN, so FSYNC is unused.
|
||||
* This GPIO is kept low to prevent spurious triggers.
|
||||
*/
|
||||
#define GPIO_42688P_FSYNC /* PC7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7)
|
||||
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PD0 VBUS sensing (active high input)
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS /* PD0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN0)
|
||||
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
|
||||
/*
|
||||
* Serial Port Mapping:
|
||||
*
|
||||
* UART Device Pins Function
|
||||
* ---- ------ ---- --------
|
||||
* USART1 /dev/ttyS0 PA9/PA10 Console/Debug
|
||||
* USART2 /dev/ttyS1 PD5/PD6 RC Input
|
||||
* USART3 /dev/ttyS2 PD8/PD9 TEL4 (DJI/MSP)
|
||||
* UART4 /dev/ttyS3 PA0/PA1 TEL1
|
||||
* UART5 /dev/ttyS4 PB13/PB12 TEL2
|
||||
* UART7 /dev/ttyS5 PE8/PE7 TEL3 (ESC Telemetry)
|
||||
* UART8 /dev/ttyS6 PE1/PE0 GPS1
|
||||
*/
|
||||
|
||||
/* RC Serial port - USART2 (PD5/PD6) */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS1"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/* This board provides the board_on_reset interface */
|
||||
#define BOARD_HAS_ON_RESET 1
|
||||
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_nLED_RED, \
|
||||
GPIO_nLED_GREEN, \
|
||||
GPIO_nLED_BLUE, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_42688P_FSYNC, \
|
||||
}
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 4
|
||||
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the board.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
/* Parameters stored in internal flash */
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,75 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file bootloader_main.c
|
||||
*
|
||||
* AirBrainH743-specific early startup code for bootloader
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
#include "bl.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_uart.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "arm_internal.h"
|
||||
#include <px4_platform_common/init.h>
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
__EXPORT void board_on_reset(int status) {}
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure USB interfaces */
|
||||
stm32_usbinitialize();
|
||||
}
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
void board_late_initialize(void)
|
||||
{
|
||||
sercon_main(0, NULL);
|
||||
}
|
||||
|
||||
extern void sys_tick_handler(void);
|
||||
void board_timerhook(void)
|
||||
{
|
||||
sys_tick_handler();
|
||||
}
|
||||
@@ -0,0 +1,85 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define APP_LOAD_ADDRESS 0x08020000
|
||||
#define BOOTLOADER_DELAY 5000
|
||||
#define INTERFACE_USB 1
|
||||
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
|
||||
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS)
|
||||
|
||||
#define INTERFACE_USART 1
|
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 1209
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (14)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
|
||||
#define OSC_FREQ 8
|
||||
|
||||
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE
|
||||
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN
|
||||
#define BOARD_LED_ON 0
|
||||
#define BOARD_LED_OFF 1
|
||||
|
||||
#define SERIAL_BREAK_DETECT_DISABLED 1
|
||||
|
||||
#if !defined(ARCH_SN_MAX_LENGTH)
|
||||
# define ARCH_SN_MAX_LENGTH 12
|
||||
#endif
|
||||
|
||||
/* Reserve 128KB (1 sector) at end of flash for parameters */
|
||||
#define APP_RESERVATION_SIZE (1 * 128 * 1024)
|
||||
|
||||
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
|
||||
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
|
||||
#endif
|
||||
|
||||
#if !defined(USB_DATA_ALIGN)
|
||||
# define USB_DATA_ALIGN
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_SELECTION
|
||||
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_FILTER_ONUSB
|
||||
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
|
||||
#endif
|
||||
|
||||
/* Boot device selection list*/
|
||||
#define USB0_DEV 0x01
|
||||
#define SERIAL0_DEV 0x02
|
||||
#define SERIAL1_DEV 0x04
|
||||
@@ -0,0 +1,47 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 <px4_arch/i2c_hw_description.h>
|
||||
|
||||
/*
|
||||
* I2C bus configuration for AirBrainH743
|
||||
*
|
||||
* I2C1: Internal bus - PB6 (SCL), PB7 (SDA)
|
||||
* Devices: DPS310 baro @ 0x76, LIS2MDL compass @ 0x1E
|
||||
* I2C4: External bus - PD12 (SCL), PD13 (SDA)
|
||||
*/
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusInternal(1),
|
||||
initI2CBusExternal(4),
|
||||
};
|
||||
@@ -0,0 +1,249 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* AirBrainH743-specific early startup code.
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <syslog.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/mtd/mtd.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "arm_internal.h"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
#include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
extern FAR struct mtd_dev_s *w25n_initialize(FAR struct spi_dev_s *dev, uint32_t spi_devid);
|
||||
#endif
|
||||
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
UNUSED(ms);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset
|
||||
*
|
||||
* Description:
|
||||
* Optionally provided function called on entry to board_system_reset
|
||||
* It should perform any house keeping prior to the rest.
|
||||
*
|
||||
* status - 1 if resetting to boot loader
|
||||
* 0 if just resetting
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_on_reset(int status)
|
||||
{
|
||||
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
|
||||
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
|
||||
}
|
||||
|
||||
if (status >= 0) {
|
||||
up_mdelay(100);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point.
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* Reset PWM first thing */
|
||||
board_on_reset(-1);
|
||||
|
||||
/* configure LEDs */
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure pins */
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
|
||||
/* configure USB interfaces */
|
||||
stm32_usbinitialize();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization.
|
||||
*
|
||||
****************************************************************************/
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
/* Need hrt running before using the ADC */
|
||||
px4_platform_init();
|
||||
|
||||
/* configure SPI interfaces */
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
led_off(LED_GREEN);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
/* Initialize W25N01GV NAND Flash on SPI2 */
|
||||
struct spi_dev_s *spi2 = stm32_spibus_initialize(2);
|
||||
|
||||
if (!spi2) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI2 for W25N\n");
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
struct mtd_dev_s *mtd = w25n_initialize(spi2, 0);
|
||||
|
||||
if (!mtd) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize W25N MTD driver\n");
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
int ret = register_mtddriver("/dev/mtd0", mtd, 0755, NULL);
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to register MTD driver: %d\n", ret);
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
syslog(LOG_INFO, "[boot] W25N MTD registered at /dev/mtd0\n");
|
||||
|
||||
#ifdef CONFIG_FS_LITTLEFS
|
||||
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, NULL);
|
||||
|
||||
if (ret == 0) {
|
||||
/* Verify the filesystem is usable by creating a test file */
|
||||
int fd = open(CONFIG_BOARD_ROOT_PATH "/.mount_test", O_CREAT | O_WRONLY | O_TRUNC);
|
||||
|
||||
if (fd >= 0) {
|
||||
close(fd);
|
||||
unlink(CONFIG_BOARD_ROOT_PATH "/.mount_test");
|
||||
|
||||
} else {
|
||||
syslog(LOG_WARNING, "[boot] littlefs mounted but not usable, reformatting\n");
|
||||
nx_umount2(CONFIG_BOARD_ROOT_PATH, 0);
|
||||
ret = -1;
|
||||
}
|
||||
}
|
||||
|
||||
if (ret < 0) {
|
||||
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, "forceformat");
|
||||
}
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to mount littlefs: %d\n", ret);
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
syslog(LOG_INFO, "[boot] LittleFS mounted at %s\n", CONFIG_BOARD_ROOT_PATH);
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
/* Initialize parameters in internal flash (sector 15, 128KB at 0x081E0000) */
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{15, 128 * 1024, 0x081E0000},
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,205 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
static bool nuttx_owns_leds = true;
|
||||
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
|
||||
# define xlat(p) xlatpx4[(p)]
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
|
||||
GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN
|
||||
GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
# define xlat(p) (p)
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_nLED_RED, // LED_RED
|
||||
GPIO_nLED_GREEN, // LED_GREEN
|
||||
GPIO_nLED_BLUE, // LED_BLUE
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
if (g_ledmap[l] != 0) {
|
||||
stm32_configgpio(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive Low to switch on (active low LEDs) */
|
||||
if (led < (int)(sizeof(g_ledmap) / sizeof(g_ledmap[0])) && g_ledmap[led] != 0) {
|
||||
stm32_gpiowrite(g_ledmap[led], !state);
|
||||
}
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
/* If Low it is on */
|
||||
if (led < (int)(sizeof(g_ledmap) / sizeof(g_ledmap[0])) && g_ledmap[led] != 0) {
|
||||
return !stm32_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), true);
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), false);
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_initialize(void)
|
||||
{
|
||||
led_init();
|
||||
}
|
||||
|
||||
void board_autoled_on(int led)
|
||||
{
|
||||
if (!nuttx_owns_leds) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
break;
|
||||
|
||||
case LED_HEAPALLOCATE:
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_IRQSENABLED:
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
break;
|
||||
|
||||
case LED_STACKCREATED:
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_INIRQ:
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_SIGNAL:
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
break;
|
||||
|
||||
case LED_ASSERTION:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_PANIC:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
break;
|
||||
|
||||
case LED_IDLE:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void board_autoled_off(int led)
|
||||
{
|
||||
if (!nuttx_owns_leds) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
break;
|
||||
|
||||
case LED_SIGNAL:
|
||||
phy_set_led(BOARD_LED_GREEN, false);
|
||||
break;
|
||||
|
||||
case LED_INIRQ:
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
break;
|
||||
|
||||
case LED_ASSERTION:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
break;
|
||||
|
||||
case LED_PANIC:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
break;
|
||||
|
||||
case LED_IDLE:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */
|
||||
@@ -0,0 +1,58 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 <px4_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
/*
|
||||
* SPI bus configuration for AirBrainH743
|
||||
*
|
||||
* SPI1: IMU (Invensensev3/ICM42688P) - PA5 SCK, PA6 MISO, PA7 MOSI, PA3 CS
|
||||
* SPI2: W25N Flash - PD3 SCK, PB14 MISO, PC3 MOSI, PD4 CS
|
||||
* SPI4: External/AUX - PE12 SCK, PE5 MISO, PE6 MOSI
|
||||
*/
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin3}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin4}), // W25N Flash
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI4, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin3}), // User 1 GPIO as chip select
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
@@ -0,0 +1,74 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
/*
|
||||
* PWM output configuration for AirBrainH743
|
||||
*
|
||||
* M1: PE14 (TIM1_CH4)
|
||||
* M2: PE13 (TIM1_CH3)
|
||||
* M3: PE11 (TIM1_CH2)
|
||||
* M4: PE9 (TIM1_CH1)
|
||||
* M5: PB0 (TIM3_CH3)
|
||||
* M6: PB1 (TIM3_CH4)
|
||||
* M7: PB10 (TIM2_CH3)
|
||||
* M8: PB11 (TIM2_CH4)
|
||||
* M9: PA2 (TIM5_CH3) - LED strip
|
||||
*
|
||||
* Note: TIM2 is shared with buzzer pin PA15 (TIM2_CH1). The buzzer is disabled
|
||||
* by default because the tone alarm driver would change the timer prescaler/ARR
|
||||
* which affects M7/M8 PWM frequency. See board_config.h for details.
|
||||
*/
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
|
||||
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
|
||||
initIOTimer(Timer::Timer2, DMA{DMA::Index1, DMA::Stream6, DMA::Channel3}),
|
||||
initIOTimer(Timer::Timer5),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), // M1
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), // M2
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), // M3
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), // M4
|
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), // M5
|
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), // M6
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}), // M7
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}), // M8
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), // M9 (LED)
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
@@ -0,0 +1,75 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
#include <stm32_otg.h>
|
||||
#include <debug.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO */
|
||||
#ifdef CONFIG_STM32H7_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
}
|
||||
@@ -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}),
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROOT_PATH="/fs/flash"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
|
||||
@@ -38,5 +38,6 @@ param set-default SYS_DM_BACKEND 1
|
||||
# Ignore that there is no SD card
|
||||
param set-default COM_ARM_SDCARD 0
|
||||
|
||||
# Disable logging
|
||||
param set-default SDLOG_BACKEND 0
|
||||
# W25N NAND flash with littlefs (128 MB): larger buffer, auto-rotate
|
||||
set LOGGER_BUF 32
|
||||
param set-default SDLOG_DIRS_MAX 3
|
||||
|
||||
@@ -99,7 +99,7 @@
|
||||
* PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
|
||||
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
|
||||
* PLL1Q = PLL1_VCO/5 = 960 MHz / 5 = 192 MHz (SPI123 clock, max 200 MHz)
|
||||
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
|
||||
*/
|
||||
|
||||
@@ -111,12 +111,12 @@
|
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120)
|
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(5)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
|
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120)
|
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 5)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
|
||||
|
||||
/* PLL2 */
|
||||
@@ -227,9 +227,9 @@
|
||||
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
|
||||
|
||||
/* SPI123 clock source */
|
||||
/* SPI123 clock source - PLL1Q = 192 MHz for W25N NAND flash (max 104 MHz) */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL1
|
||||
|
||||
/* SPI45 clock source */
|
||||
|
||||
@@ -281,17 +281,17 @@
|
||||
|
||||
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
|
||||
/* 25 MHz Max for now, 25 mHz = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* PLL1Q = 192 MHz, div = 192 / 50 = 3.84, round up to 4 for 24 MHz
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (4 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (4 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
@@ -33,6 +33,10 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
/* SPI1 DMA for W25N NAND Flash */
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1 */
|
||||
|
||||
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2 */
|
||||
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */
|
||||
|
||||
|
||||
@@ -104,6 +104,10 @@ CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_FS_LITTLEFS=y
|
||||
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
|
||||
CONFIG_FS_LITTLEFS_READ_SIZE_FACTOR=1
|
||||
CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=1
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
@@ -126,7 +130,9 @@ CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
# CONFIG_MTD_RAMTRON is not set
|
||||
CONFIG_MTD_W25N=y
|
||||
CONFIG_W25N_SPIFREQUENCY=104000000
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
@@ -135,7 +141,7 @@ CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_MMCSDSPIPORTNO=1
|
||||
# CONFIG_NSH_MMCSDSPIPORTNO is not set
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
@@ -148,9 +154,6 @@ CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
|
||||
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
@@ -188,6 +191,7 @@ CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DMAMUX1=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
@@ -202,6 +206,8 @@ CONFIG_STM32H7_SDMMC1=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI4=y
|
||||
CONFIG_STM32H7_SPI4_DMA=y
|
||||
|
||||
@@ -59,6 +59,11 @@
|
||||
# define BOARD_HAS_NBAT_V 1
|
||||
# define BOARD_HAS_NBAT_I 1
|
||||
|
||||
/* Enable small flash logging support (for W25N NAND flash) */
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
# define BOARD_SMALL_FLASH_LOGGING 1
|
||||
#endif
|
||||
|
||||
/* Holybro KakuteH7 GPIOs ************************************************************************/
|
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
|
||||
|
||||
@@ -59,6 +59,8 @@
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/gran.h>
|
||||
#include <nuttx/mtd/mtd.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_uart.h>
|
||||
#include <arch/board/board.h>
|
||||
@@ -79,6 +81,10 @@
|
||||
# include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
extern FAR struct mtd_dev_s *w25n_initialize(FAR struct spi_dev_s *dev, uint32_t spi_devid);
|
||||
#endif
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
@@ -231,14 +237,49 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
/* Get the SPI port for the microSD slot */
|
||||
struct spi_dev_s *spi_dev = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
/* Initialize W25N01GV NAND Flash on SPI1 */
|
||||
struct spi_dev_s *spi1 = stm32_spibus_initialize(1);
|
||||
|
||||
if (!spi_dev) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
|
||||
led_on(LED_BLUE);
|
||||
if (!spi1) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI1 for W25N\n");
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
struct mtd_dev_s *mtd = w25n_initialize(spi1, 0);
|
||||
|
||||
if (!mtd) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize W25N MTD driver\n");
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
int ret = register_mtddriver("/dev/mtd0", mtd, 0755, NULL);
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to register MTD driver: %d\n", ret);
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
syslog(LOG_INFO, "[boot] W25N MTD registered at /dev/mtd0\n");
|
||||
|
||||
#ifdef CONFIG_FS_LITTLEFS
|
||||
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, "autoformat");
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to mount littlefs: %d\n", ret);
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
syslog(LOG_INFO, "[boot] LittleFS mounted at %s\n", CONFIG_BOARD_ROOT_PATH);
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
up_udelay(20);
|
||||
|
||||
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(SPIDEV_MMCSD(0), SPI::CS{GPIO::PortA, GPIO::Pin4})
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortA, GPIO::Pin4}) // W25N01GV NAND Flash
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}),
|
||||
|
||||
Submodule boards/modalai/voxl2/libfc-sensor-api updated: 85151aaf6b...d5abf9cbbf
@@ -178,6 +178,7 @@
|
||||
- [CubePilot Cube Orange (CubePilot)](flight_controller/cubepilot_cube_orange.md)
|
||||
- [CubePilot Cube Yellow (CubePilot)](flight_controller/cubepilot_cube_yellow.md)
|
||||
- [Cube Wiring Quickstart](assembly/quick_start_cube.md)
|
||||
- [Gear Up AirBrainH743](flight_controller/gearup_airbrainh743.md)
|
||||
- [Holybro Kakute H7v2](flight_controller/kakuteh7v2.md)
|
||||
- [Holybro Kakute H7mini](flight_controller/kakuteh7mini.md)
|
||||
- [Holybro Kakute H7](flight_controller/kakuteh7.md)
|
||||
|
||||
@@ -25,6 +25,7 @@ The boards in this category are:
|
||||
- [CubePilot Cube Orange+](../flight_controller/cubepilot_cube_orangeplus.md)
|
||||
- [CubePilot Cube Orange](../flight_controller/cubepilot_cube_orange.md)
|
||||
- [CubePilot Cube Yellow](../flight_controller/cubepilot_cube_yellow.md)
|
||||
- [Gear Up AirBrainH743](../flight_controller/gearup_airbrainh743.md)
|
||||
- [Holybro Kakute H7v2](../flight_controller/kakuteh7v2.md)
|
||||
- [Holybro Kakute H7mini](../flight_controller/kakuteh7mini.md)
|
||||
- [Holybro Kakute H7](../flight_controller/kakuteh7.md)
|
||||
|
||||
@@ -0,0 +1,96 @@
|
||||
# Gear Up AirBrainH743
|
||||
|
||||
:::warning
|
||||
PX4 does not manufacture this (or any) autopilot.
|
||||
Contact the [manufacturer](https://takeyourgear.com/) for hardware support.
|
||||
:::
|
||||
|
||||
::: info
|
||||
This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
|
||||
:::
|
||||
|
||||
Purchase from [takeyourgear.com](https://takeyourgear.com/pages/products/airbrain).
|
||||
|
||||
For more information and pinout, check the [GitHub documentation](https://github.com/GearUp-Company/AirBrainH743).
|
||||
|
||||
## Key Features
|
||||
|
||||
- MCU: STM32H743 32-bit processor running at 480 MHz
|
||||
- IMU: ICM42688P
|
||||
- Barometer: DPS310
|
||||
- Magnetometer: LIS2MDL (internal)
|
||||
- 128MB NAND Flash for logging (W25N)
|
||||
- 7x UARTs
|
||||
- I2C, SPI
|
||||
- 9x PWM Outputs (8 Motor outputs, 1 LED strip)
|
||||
- Battery input voltage: 3S-10S
|
||||
- Battery voltage/current monitoring
|
||||
- 5V@2A and 10V@2.5A BEC outputs
|
||||
- USB Type-C (IP68)
|
||||
- EMC and ESD protection
|
||||
|
||||
## Connectors and Pins
|
||||
|
||||
:::warning
|
||||
The pin order is different from the Pixhawk standard (compatible to the Betaflight standard).
|
||||
:::
|
||||
|
||||
### UARTs
|
||||
|
||||
Current UART configuration:
|
||||
|
||||
| UART | Device | Function |
|
||||
| ------ | ---------- | ---------------------------- |
|
||||
| USART1 | /dev/ttyS0 | Console/Debug |
|
||||
| USART2 | /dev/ttyS1 | RC Input |
|
||||
| USART3 | /dev/ttyS2 | TEL4 (DJI/MSP) |
|
||||
| UART4 | /dev/ttyS3 | TEL1 |
|
||||
| UART5 | /dev/ttyS4 | TEL2 |
|
||||
| UART7 | /dev/ttyS5 | TEL3 (ESC Telemetry) |
|
||||
| UART8 | /dev/ttyS6 | GPS1 |
|
||||
|
||||
### Motor/Servo Outputs
|
||||
|
||||
| Connector | Pin | Function |
|
||||
| ----------| ------------------ |
|
||||
| ESC | M1 | Motor 1 |
|
||||
| ESC | M2 | Motor 2 |
|
||||
| ESC | M3 | Motor 3 |
|
||||
| ESC | M4 | Motor 4 |
|
||||
| PWM | M5 | Motor 5 |
|
||||
| PWM | M6 | Motor 6 |
|
||||
| PWM | M7 | Motor 7 |
|
||||
| PWM | M8 | Motor 8 |
|
||||
| AUX | M9 | LED/PWM/etc. |
|
||||
|
||||
<a id="bootloader"></a>
|
||||
|
||||
## PX4 Bootloader Update
|
||||
|
||||
Before PX4 firmware can be installed, the _PX4 bootloader_ must be flashed.
|
||||
Download the [gearup_airbrainh743_bootloader.bin](https://github.com/PX4/PX4-Autopilot/blob/main/boards/gearup/airbrainh743/extras/gearup_airbrainh743_bootloader.bin) bootloader binary and read [this page](../advanced_config/bootloader_update_from_betaflight.md) for flashing instructions.
|
||||
|
||||
## Building Firmware
|
||||
|
||||
To [build PX4](../dev_setup/building_px4.md) for this target:
|
||||
|
||||
```
|
||||
make gearup_airbrainh743_default
|
||||
```
|
||||
|
||||
## Installing PX4 Firmware
|
||||
|
||||
Firmware can be installed in any of the normal ways:
|
||||
|
||||
- Build and upload the source:
|
||||
|
||||
```
|
||||
make gearup_airbrainh743_default upload
|
||||
```
|
||||
|
||||
- [Load the firmware](../config/firmware.md) using _QGroundControl_.
|
||||
You can use either pre-built firmware or your own custom firmware.
|
||||
|
||||
### System Console
|
||||
|
||||
UART1 (ttyS0) is configured for use as the [System Console](../debug/system_console.md).
|
||||
@@ -27,7 +27,7 @@ Unless the mode is safety-critical, requires strict timing or very high update r
|
||||
|
||||
::: tip
|
||||
If you want to use Python, check out the [examples in the repository](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/python).
|
||||
Not all classes have Python bindings yet — the [supported bindings are here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_py/src/px4_ros2).
|
||||
Not all classes have Python bindings yet — the [supported bindings are here](https://auterion.github.io/px4-ros2-interface-lib/python/index.html).
|
||||
You are welcome to add and contribute missing classes.
|
||||
:::
|
||||
|
||||
|
||||
@@ -69,6 +69,8 @@ set(msg_files
|
||||
DistanceSensorModeChangeRequest.msg
|
||||
DronecanNodeStatus.msg
|
||||
Ekf2Timestamps.msg
|
||||
EscEepromRead.msg
|
||||
EscEepromWrite.msg
|
||||
EscReport.msg
|
||||
EscStatus.msg
|
||||
EstimatorAidSource1d.msg
|
||||
|
||||
@@ -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
|
||||
@@ -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
@@ -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
@@ -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
|
||||
|
||||
@@ -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)
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -2,6 +2,7 @@
|
||||
#include <px4_platform_common/time.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include "apps.h"
|
||||
|
||||
@@ -43,6 +44,7 @@ void list_builtins(apps_map_type &apps)
|
||||
int shutdown_main(int argc, char *argv[])
|
||||
{
|
||||
printf("Exiting NOW.\n");
|
||||
uorb_shutdown();
|
||||
system_exit(0);
|
||||
}
|
||||
|
||||
|
||||
@@ -49,6 +49,7 @@
|
||||
|
||||
#include <px4_platform_common/external_reset_lockout.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <errno.h>
|
||||
@@ -173,6 +174,8 @@ static void shutdown_worker(void *arg)
|
||||
const bool delay_elapsed = (now > shutdown_time_us);
|
||||
|
||||
if (delay_elapsed && ((done && shutdown_lock_counter == 0) || (now > (shutdown_time_us + shutdown_timeout_us)))) {
|
||||
uorb_shutdown();
|
||||
|
||||
if (shutdown_args & SHUTDOWN_ARG_REBOOT) {
|
||||
#if defined(CONFIG_BOARDCTL_RESET)
|
||||
PX4_INFO_RAW("Reboot NOW.");
|
||||
|
||||
@@ -51,6 +51,7 @@
|
||||
#include <sys/boardctl.h>
|
||||
#endif
|
||||
|
||||
|
||||
static uORB::DeviceMaster *g_dev = nullptr;
|
||||
|
||||
int uorb_start(void)
|
||||
@@ -113,6 +114,18 @@ int uorb_top(char **topic_filter, int num_filters)
|
||||
return OK;
|
||||
}
|
||||
|
||||
void uorb_shutdown(void)
|
||||
{
|
||||
#ifdef CONFIG_ORB_COMMUNICATOR
|
||||
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
|
||||
|
||||
if (ch) {
|
||||
ch->shutdown();
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ORB_COMMUNICATOR */
|
||||
}
|
||||
|
||||
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
|
||||
{
|
||||
return uORB::Manager::get_instance()->orb_advertise(meta, data);
|
||||
|
||||
@@ -121,6 +121,7 @@ __BEGIN_DECLS
|
||||
int uorb_start(void);
|
||||
int uorb_status(void);
|
||||
int uorb_top(char **topic_filter, int num_filters);
|
||||
void uorb_shutdown(void);
|
||||
|
||||
/**
|
||||
* ORB topic advertiser handle.
|
||||
|
||||
@@ -129,6 +129,22 @@ public:
|
||||
|
||||
virtual int16_t send_message(const char *messageName, int32_t length, uint8_t *data) = 0;
|
||||
|
||||
|
||||
//=========================================================================
|
||||
// INTERFACES FOR Lifecycle messages
|
||||
//=========================================================================
|
||||
|
||||
/**
|
||||
* @brief Interface to notify the remote entity of a shutdown.
|
||||
*
|
||||
* @return
|
||||
* 0 = success; This means the shutdown is successfully sent to the receiver
|
||||
* Note: This does not mean that the receiver has received it.
|
||||
* otherwise = failure.
|
||||
*/
|
||||
|
||||
virtual int16_t shutdown() { return 0; }
|
||||
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
Submodule platforms/nuttx/NuttX/nuttx updated: 201d8b01f1...f34ff89edf
@@ -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
@@ -51,7 +51,7 @@
|
||||
#include <errno.h>
|
||||
#include "hrt_work.h"
|
||||
|
||||
// Voxl2 board specific API definitions to get time offset
|
||||
// Voxl board specific API definitions to get time
|
||||
#if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
|
||||
#include "fc_sensor.h"
|
||||
#endif
|
||||
@@ -112,29 +112,6 @@ hrt_abstime hrt_absolute_time()
|
||||
#else // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
struct timespec ts;
|
||||
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
|
||||
# if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
|
||||
hrt_abstime temp_abstime = ts_to_abstime(&ts);
|
||||
int apps_time_offset = fc_sensor_get_time_offset();
|
||||
|
||||
if (apps_time_offset < 0) {
|
||||
hrt_abstime temp_offset = -apps_time_offset;
|
||||
|
||||
if (temp_offset >= temp_abstime) {
|
||||
temp_abstime = 0;
|
||||
|
||||
} else {
|
||||
temp_abstime -= temp_offset;
|
||||
}
|
||||
|
||||
} else {
|
||||
temp_abstime += (hrt_abstime) apps_time_offset;
|
||||
}
|
||||
|
||||
ts.tv_sec = temp_abstime / 1000000;
|
||||
ts.tv_nsec = (temp_abstime % 1000000) * 1000;
|
||||
# endif // defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
|
||||
|
||||
return ts_to_abstime(&ts);
|
||||
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
}
|
||||
@@ -476,8 +453,21 @@ int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
|
||||
}
|
||||
|
||||
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
return system_clock_gettime(clk_id, tp);
|
||||
|
||||
int rv = system_clock_gettime(clk_id, tp);
|
||||
|
||||
# if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
|
||||
|
||||
// On VOXL use DSP clock as reference for MONOTONIC
|
||||
if (clk_id == CLOCK_MONOTONIC) {
|
||||
hrt_abstime temp_abstime = fc_sensor_get_dsp_timestamp_us();
|
||||
tp->tv_sec = temp_abstime / 1000000;
|
||||
tp->tv_nsec = (temp_abstime % 1000000) * 1000;
|
||||
}
|
||||
|
||||
# endif // defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
|
||||
|
||||
return rv;
|
||||
}
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
|
||||
@@ -73,6 +73,7 @@
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include "apps.h"
|
||||
#include "px4_daemon/client.h"
|
||||
@@ -505,6 +506,7 @@ void sig_int_handler(int sig_num)
|
||||
fflush(stdout);
|
||||
printf("\nPX4 Exiting...\n");
|
||||
fflush(stdout);
|
||||
uorb_shutdown();
|
||||
px4_daemon::Pxh::stop();
|
||||
_exit_requested = true;
|
||||
}
|
||||
|
||||
@@ -19,6 +19,10 @@ actuator_output:
|
||||
label: 'ESC 3 Spin Direction'
|
||||
- param: 'VOXL_ESC_SDIR4'
|
||||
label: 'ESC 4 Spin Direction'
|
||||
- param: 'VOXL_ESC_CMD'
|
||||
label: 'ESC Command Type'
|
||||
- param: 'VOXL_ESC_PWR_MIN'
|
||||
label: 'ESC Minimum Power With PWM Command Type'
|
||||
output_groups:
|
||||
- param_prefix: VOXL_ESC
|
||||
group_label: 'ESCs'
|
||||
|
||||
@@ -300,6 +300,7 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map)
|
||||
param_get(param_find("VOXL_ESC_SDIR3"), ¶ms->direction_map[2]);
|
||||
param_get(param_find("VOXL_ESC_SDIR4"), ¶ms->direction_map[3]);
|
||||
|
||||
param_get(param_find("VOXL_ESC_PWR_MIN"), ¶ms->pwr_min);
|
||||
param_get(param_find("VOXL_ESC_RPM_MIN"), ¶ms->rpm_min);
|
||||
param_get(param_find("VOXL_ESC_RPM_MAX"), ¶ms->rpm_max);
|
||||
|
||||
@@ -311,10 +312,23 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map)
|
||||
|
||||
param_get(param_find("VOXL_ESC_GPIO_CH"), ¶ms->gpio_ctl_channel);
|
||||
|
||||
if (params->rpm_min >= params->rpm_max) {
|
||||
PX4_ERR("Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters.");
|
||||
params->rpm_min = 0;
|
||||
ret = PX4_ERROR;
|
||||
param_get(param_find("VOXL_ESC_CMD"), ¶ms->cmd_type);
|
||||
|
||||
if (params->cmd_type > VOXL_ESC_PWM_CMDS) {
|
||||
PX4_WARN("Warning, VOXL_ESC_CMD set to invalid value %d. Using 1 instead", (int) params->cmd_type);
|
||||
params->cmd_type = VOXL_ESC_PWM_CMDS;
|
||||
|
||||
} else if (params->cmd_type < VOXL_ESC_RPM_CMDS) {
|
||||
PX4_WARN("Warning, VOXL_ESC_CMD set to invalid value %d. Using 0 instead", (int) params->cmd_type);
|
||||
params->cmd_type = VOXL_ESC_RPM_CMDS;
|
||||
}
|
||||
|
||||
if (params->cmd_type == VOXL_ESC_RPM_CMDS) {
|
||||
if (params->rpm_min >= params->rpm_max) {
|
||||
PX4_ERR("Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters.");
|
||||
params->rpm_min = 0;
|
||||
ret = PX4_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
if (params->turtle_motor_percent < 0 || params->turtle_motor_percent > 100) {
|
||||
@@ -392,19 +406,24 @@ int VoxlEsc::task_spawn(int argc, char *argv[])
|
||||
int ch;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "dv", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'd':
|
||||
_device = argv[myoptind];
|
||||
break;
|
||||
VoxlEsc *instance = new VoxlEsc();
|
||||
|
||||
default:
|
||||
break;
|
||||
// Parse any passed in options
|
||||
if ((argc > 1) && (argv[1] != nullptr)) {
|
||||
while ((ch = px4_getopt(argc - 1, &argv[1], "d:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'd':
|
||||
_device = argv[myoptind];
|
||||
PX4_INFO("Configuring device as %s", _device);
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("Unknown option: %c", ch);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
VoxlEsc *instance = new VoxlEsc();
|
||||
|
||||
if (instance) {
|
||||
_object.store(instance);
|
||||
_task_id = task_id_is_work_queue;
|
||||
@@ -571,6 +590,8 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
|
||||
QC_ESC_FB_POWER_STATUS packet;
|
||||
memcpy(&packet, _fb_packet.buffer, packet_size);
|
||||
|
||||
_rx_power_status_count++;
|
||||
|
||||
float voltage = packet.voltage * 0.001f; // Voltage is reported at 1 mV resolution
|
||||
float current = packet.current * 0.008f; // Total current is reported at 8mA resolution
|
||||
|
||||
@@ -907,8 +928,19 @@ int VoxlEsc::update_params()
|
||||
if (ret == PX4_OK) {
|
||||
_mixing_output.setAllDisarmedValues(0);
|
||||
_mixing_output.setAllFailsafeValues(0);
|
||||
_mixing_output.setAllMinValues(_parameters.rpm_min);
|
||||
_mixing_output.setAllMaxValues(_parameters.rpm_max);
|
||||
|
||||
if (_parameters.cmd_type == VOXL_ESC_RPM_CMDS) {
|
||||
_mixing_output.setAllMinValues(_parameters.rpm_min);
|
||||
_mixing_output.setAllMaxValues(_parameters.rpm_max);
|
||||
|
||||
} else if (_parameters.cmd_type == VOXL_ESC_PWM_CMDS) {
|
||||
// we use a minimum value of 1, since 0 is for disarmed
|
||||
_min_active_pwm = math::constrain(static_cast<int>((_parameters.pwr_min *
|
||||
static_cast<float>(VOXL_ESC_PWM_MAX))),
|
||||
VOXL_ESC_PWM_MIN, VOXL_ESC_PWM_MAX);
|
||||
_mixing_output.setAllMinValues(_min_active_pwm);
|
||||
_mixing_output.setAllMaxValues(VOXL_ESC_PWM_MAX);
|
||||
}
|
||||
|
||||
_rpm_fullscale = _parameters.rpm_max - _parameters.rpm_min;
|
||||
}
|
||||
@@ -1216,11 +1248,18 @@ bool VoxlEsc::updateOutputs(uint16_t outputs[MAX_ACTUATORS],
|
||||
_esc_chans[i].rate_req = 0;
|
||||
|
||||
} else {
|
||||
if (_extended_rpm) {
|
||||
if (outputs[i] > VOXL_ESC_RPM_MAX_EXT) { outputs[i] = VOXL_ESC_RPM_MAX_EXT; }
|
||||
if ((_turtle_mode_en) || (_parameters.cmd_type == VOXL_ESC_RPM_CMDS)) {
|
||||
if (_extended_rpm) {
|
||||
if (outputs[i] > VOXL_ESC_RPM_MAX_EXT) { outputs[i] = VOXL_ESC_RPM_MAX_EXT; }
|
||||
|
||||
} else {
|
||||
if (outputs[i] > VOXL_ESC_RPM_MAX) { outputs[i] = VOXL_ESC_RPM_MAX; }
|
||||
} else {
|
||||
if (outputs[i] > VOXL_ESC_RPM_MAX) { outputs[i] = VOXL_ESC_RPM_MAX; }
|
||||
}
|
||||
|
||||
} else if (_parameters.cmd_type == VOXL_ESC_PWM_CMDS) {
|
||||
if (outputs[i] > VOXL_ESC_PWM_MAX) { outputs[i] = VOXL_ESC_PWM_MAX; }
|
||||
|
||||
else if (outputs[i] < _min_active_pwm) { outputs[i] = _min_active_pwm; }
|
||||
}
|
||||
|
||||
if (!_turtle_mode_en) {
|
||||
@@ -1235,18 +1274,34 @@ bool VoxlEsc::updateOutputs(uint16_t outputs[MAX_ACTUATORS],
|
||||
|
||||
|
||||
Command cmd;
|
||||
cmd.len = qc_esc_create_rpm_packet4_fb(_esc_chans[0].rate_req,
|
||||
_esc_chans[1].rate_req,
|
||||
_esc_chans[2].rate_req,
|
||||
_esc_chans[3].rate_req,
|
||||
_esc_chans[0].led,
|
||||
_esc_chans[1].led,
|
||||
_esc_chans[2].led,
|
||||
_esc_chans[3].led,
|
||||
_fb_idx,
|
||||
cmd.buf,
|
||||
sizeof(cmd.buf),
|
||||
_extended_rpm);
|
||||
|
||||
if (_parameters.cmd_type == VOXL_ESC_RPM_CMDS) {
|
||||
cmd.len = qc_esc_create_rpm_packet4_fb(_esc_chans[0].rate_req,
|
||||
_esc_chans[1].rate_req,
|
||||
_esc_chans[2].rate_req,
|
||||
_esc_chans[3].rate_req,
|
||||
_esc_chans[0].led,
|
||||
_esc_chans[1].led,
|
||||
_esc_chans[2].led,
|
||||
_esc_chans[3].led,
|
||||
_fb_idx,
|
||||
cmd.buf,
|
||||
sizeof(cmd.buf),
|
||||
_extended_rpm);
|
||||
|
||||
} else if (_parameters.cmd_type == VOXL_ESC_PWM_CMDS) {
|
||||
cmd.len = qc_esc_create_pwm_packet4_fb(_esc_chans[0].rate_req,
|
||||
_esc_chans[1].rate_req,
|
||||
_esc_chans[2].rate_req,
|
||||
_esc_chans[3].rate_req,
|
||||
_esc_chans[0].led,
|
||||
_esc_chans[1].led,
|
||||
_esc_chans[2].led,
|
||||
_esc_chans[3].led,
|
||||
_fb_idx,
|
||||
cmd.buf,
|
||||
sizeof(cmd.buf));
|
||||
}
|
||||
|
||||
if (_uart_port.write(cmd.buf, cmd.len) != cmd.len) {
|
||||
PX4_ERR("Failed to send packet");
|
||||
@@ -1631,6 +1686,8 @@ void VoxlEsc::print_params()
|
||||
PX4_INFO("Params: VOXL_ESC_SDIR3: %" PRId32, _parameters.direction_map[2]);
|
||||
PX4_INFO("Params: VOXL_ESC_SDIR4: %" PRId32, _parameters.direction_map[3]);
|
||||
|
||||
PX4_INFO("Params: VOXL_ESC_PWR_MIN: %f", (double) _parameters.pwr_min);
|
||||
|
||||
PX4_INFO("Params: VOXL_ESC_RPM_MIN: %" PRId32, _parameters.rpm_min);
|
||||
PX4_INFO("Params: VOXL_ESC_RPM_MAX: %" PRId32, _parameters.rpm_max);
|
||||
|
||||
@@ -1647,6 +1704,8 @@ void VoxlEsc::print_params()
|
||||
PX4_INFO("Params: VOXL_ESC_T_OVER: %" PRId32, _parameters.esc_over_temp_threshold);
|
||||
|
||||
PX4_INFO("Params: VOXL_ESC_GPIO_CH: %" PRId32, _parameters.gpio_ctl_channel);
|
||||
|
||||
PX4_INFO("Params: VOXL_ESC_CMD: %" PRId32, _parameters.cmd_type);
|
||||
}
|
||||
|
||||
int VoxlEsc::print_status()
|
||||
@@ -1656,6 +1715,10 @@ int VoxlEsc::print_status()
|
||||
PX4_INFO("UART port: %s", _device);
|
||||
PX4_INFO("UART open: %s", _uart_port.isOpen() ? "yes" : "no");
|
||||
|
||||
PX4_INFO("CRC error count: %lu", (long unsigned int) _rx_crc_error_count);
|
||||
PX4_INFO("Packet RX count: %lu", (long unsigned int) _rx_packet_count);
|
||||
PX4_INFO("Power status count: %lu", (long unsigned int) _rx_power_status_count);
|
||||
|
||||
PX4_INFO("");
|
||||
print_params();
|
||||
PX4_INFO("");
|
||||
@@ -1695,6 +1758,7 @@ const char * VoxlEsc::board_id_to_name(int board_id)
|
||||
case 40: return "ModalAi 4-in-1 ESC (M0129-3)";
|
||||
case 41: return "ModalAi 4-in-1 ESC (M0134-6)";
|
||||
case 42: return "ModalAi 4-in-1 ESC (M0138-1)";
|
||||
case 44: return "ModalAi 4-in-1 ESC (M0129-6)";
|
||||
default: return "Unknown Board";
|
||||
}
|
||||
}
|
||||
|
||||
@@ -117,8 +117,8 @@ private:
|
||||
|
||||
static constexpr uint16_t DISARMED_VALUE = 0;
|
||||
|
||||
static constexpr uint16_t VOXL_ESC_PWM_MIN = 0;
|
||||
static constexpr uint16_t VOXL_ESC_PWM_MAX = 800;
|
||||
static constexpr int VOXL_ESC_PWM_MIN = 1;
|
||||
static constexpr int VOXL_ESC_PWM_MAX = 800;
|
||||
static constexpr uint16_t VOXL_ESC_DEFAULT_RPM_MIN = 5000;
|
||||
static constexpr uint16_t VOXL_ESC_DEFAULT_RPM_MAX = 17000;
|
||||
|
||||
@@ -148,6 +148,9 @@ private:
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX5 = 5;
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX6 = 6;
|
||||
|
||||
static constexpr int32_t VOXL_ESC_RPM_CMDS = 0;
|
||||
static constexpr int32_t VOXL_ESC_PWM_CMDS = 1;
|
||||
|
||||
Serial _uart_port{};
|
||||
|
||||
typedef struct {
|
||||
@@ -159,6 +162,7 @@ private:
|
||||
float turtle_stick_minf{0.15f};
|
||||
float turtle_cosphi{0.99f};
|
||||
int32_t baud_rate{VOXL_ESC_DEFAULT_BAUD};
|
||||
float pwr_min{0.05f};
|
||||
int32_t rpm_min{VOXL_ESC_DEFAULT_RPM_MIN};
|
||||
int32_t rpm_max{VOXL_ESC_DEFAULT_RPM_MAX};
|
||||
int32_t function_map[VOXL_ESC_OUTPUT_CHANNELS] {0, 0, 0, 0};
|
||||
@@ -169,6 +173,7 @@ private:
|
||||
int32_t esc_warn_temp_threshold{0};
|
||||
int32_t esc_over_temp_threshold{0};
|
||||
int32_t gpio_ctl_channel{0};
|
||||
int32_t cmd_type{0};
|
||||
} voxl_esc_params_t;
|
||||
|
||||
struct EscChan {
|
||||
@@ -222,6 +227,8 @@ private:
|
||||
bool _need_version_info{true};
|
||||
QC_ESC_EXTENDED_VERSION_INFO _version_info[VOXL_ESC_OUTPUT_CHANNELS];
|
||||
|
||||
int _min_active_pwm{1};
|
||||
|
||||
voxl_esc_params_t _parameters;
|
||||
int update_params();
|
||||
int load_params(voxl_esc_params_t *params, ch_assign_t *map);
|
||||
@@ -250,12 +257,13 @@ private:
|
||||
int _fb_idx;
|
||||
uint32_t _rx_crc_error_count{0};
|
||||
uint32_t _rx_packet_count{0};
|
||||
uint32_t _rx_power_status_count{0};
|
||||
|
||||
static const uint8_t READ_BUF_SIZE = 128;
|
||||
uint8_t _read_buf[READ_BUF_SIZE];
|
||||
|
||||
Battery _battery;
|
||||
static constexpr unsigned _battery_report_interval{100_ms};
|
||||
static constexpr unsigned _battery_report_interval{20_ms};
|
||||
hrt_abstime _last_battery_report_time;
|
||||
hrt_abstime _last_uart_passthru{0};
|
||||
|
||||
|
||||
@@ -276,3 +276,31 @@ PARAM_DEFINE_INT32(VOXL_ESC_T_OVER, 0);
|
||||
* @max 6
|
||||
*/
|
||||
PARAM_DEFINE_INT32(VOXL_ESC_GPIO_CH, 0);
|
||||
|
||||
/**
|
||||
* UART ESC command type
|
||||
*
|
||||
* Selects between RPM or PWM commands
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @group VOXL ESC
|
||||
* @value 0 - RPM
|
||||
* @value 1 - PWM
|
||||
* @min 0
|
||||
* @max 1
|
||||
*/
|
||||
PARAM_DEFINE_INT32(VOXL_ESC_CMD, 0);
|
||||
|
||||
/**
|
||||
* UART ESC Minimum motor power
|
||||
*
|
||||
* Minimum motor power for ESC when VOXL_ESC_CMD is set for PWM.
|
||||
* Make sure to set this high enough so that the motors are always spinning
|
||||
* while armed.
|
||||
*
|
||||
* @group VOXL ESC
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(VOXL_ESC_PWR_MIN, 0.05);
|
||||
|
||||
+57
-51
@@ -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
|
||||
|
||||
@@ -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
File diff suppressed because it is too large
Load Diff
+147
-92
@@ -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
|
||||
)
|
||||
};
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -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};
|
||||
};
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
@@ -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
|
||||
};
|
||||
@@ -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
|
||||
|
||||
+1
-1
Submodule src/drivers/gps/devices updated: a213f386d3...5ed844c374
@@ -786,6 +786,13 @@ GPS::run()
|
||||
param_get(handle, &gps_ubx_min_elev);
|
||||
}
|
||||
|
||||
int32_t gps_ubx_rate = 0;
|
||||
handle = param_find("GPS_UBX_RATE");
|
||||
|
||||
if (handle != PARAM_INVALID) {
|
||||
param_get(handle, &gps_ubx_rate);
|
||||
}
|
||||
|
||||
handle = param_find("GPS_UBX_MODE");
|
||||
|
||||
GPSDriverUBX::UBXMode ubx_mode{GPSDriverUBX::UBXMode::Normal};
|
||||
@@ -851,6 +858,13 @@ GPS::run()
|
||||
param_get(handle, &ppk_output);
|
||||
}
|
||||
|
||||
handle = param_find("GPS_UBX_JAM_DET");
|
||||
int32_t jam_det_sensitivity_hi = 1;
|
||||
|
||||
if (handle != PARAM_INVALID) {
|
||||
param_get(handle, &jam_det_sensitivity_hi);
|
||||
}
|
||||
|
||||
int32_t gnssSystemsParam = static_cast<int32_t>(GPSHelper::GNSSSystemsMask::RECEIVER_DEFAULTS);
|
||||
|
||||
if (_instance == Instance::Main) {
|
||||
@@ -938,9 +952,11 @@ GPS::run()
|
||||
.dgnss_timeout = (uint8_t)gps_ubx_dgnss_to,
|
||||
.min_cno = (uint8_t)gps_ubx_min_cno,
|
||||
.min_elev = (int8_t)gps_ubx_min_elev,
|
||||
.output_rate = (uint8_t)gps_ubx_rate,
|
||||
.heading_offset = heading_offset,
|
||||
.uart2_baudrate = f9p_uart2_baudrate,
|
||||
.ppk_output = ppk_output > 0,
|
||||
.jam_det_sensitivity_hi = jam_det_sensitivity_hi > 0,
|
||||
.mode = ubx_mode,
|
||||
};
|
||||
|
||||
|
||||
@@ -114,6 +114,25 @@ PARAM_DEFINE_INT32(GPS_UBX_MIN_CNO, 0);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GPS_UBX_MIN_ELEV, 0);
|
||||
|
||||
/**
|
||||
* u-blox GPS output rate
|
||||
*
|
||||
* Configure the output rate of u-blox GPS receivers (protocol v27+).
|
||||
* When set to 0, automatic rate selection is used based on the receiver model.
|
||||
* Default rates: M9N=8Hz, F9P L1L2=5Hz, F9P L1L5=5Hz, Others=10Hz.
|
||||
*
|
||||
* Note: Higher rates reduce satellite count (e.g., >8Hz limits to 16 SVs on M9N).
|
||||
* Max rates vary by model and RTK mode: F9P L1L2=5-7Hz, F9P L1L5=7-8Hz, X20=25Hz.
|
||||
* High rates at 115200 baud may cause dropouts.
|
||||
*
|
||||
* @min 0
|
||||
* @max 25
|
||||
* @unit Hz
|
||||
* @reboot_required true
|
||||
* @group GPS
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GPS_UBX_RATE, 0);
|
||||
|
||||
/**
|
||||
* Enable sat info (if available)
|
||||
*
|
||||
@@ -198,6 +217,20 @@ PARAM_DEFINE_INT32(GPS_UBX_CFG_INTF, 0);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GPS_UBX_PPK, 0);
|
||||
|
||||
/**
|
||||
* u-blox GPS jamming detection high sensitivity mode
|
||||
*
|
||||
* Enables or disables the high sensitivity mode for the u-blox jamming detection
|
||||
* (CFG-SEC-JAMDET_SENSITIVITY_HI). When enabled, the receiver uses a
|
||||
* more sensitive algorithm to detect jamming. Disabling this may reduce false
|
||||
* positives in electrically noisy environments.
|
||||
*
|
||||
* @boolean
|
||||
* @reboot_required true
|
||||
* @group GPS
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GPS_UBX_JAM_DET, 1);
|
||||
|
||||
/**
|
||||
* Wipes the flash config of UBX modules.
|
||||
*
|
||||
|
||||
@@ -254,11 +254,11 @@ VOXLPM::print_status()
|
||||
|
||||
switch (_pm_type) {
|
||||
case VOXLPM_TYPE_V2_LTC:
|
||||
printf("- V2 (LTC2964)\n");
|
||||
PX4_INFO("- V2 (LTC2964)");
|
||||
break;
|
||||
|
||||
case VOXLPM_TYPE_V3_INA:
|
||||
printf("- V3 (INA231)\n");
|
||||
PX4_INFO("- V3 (INA231)");
|
||||
break;
|
||||
|
||||
default:
|
||||
@@ -267,27 +267,27 @@ VOXLPM::print_status()
|
||||
|
||||
switch (_ch_type) {
|
||||
case VOXLPM_CH_TYPE_VBATT:
|
||||
printf("- type: BATT\n");
|
||||
PX4_INFO("- type: BATT");
|
||||
break;
|
||||
|
||||
case VOXLPM_CH_TYPE_P5VDC:
|
||||
printf("- type: P5VDC\n");
|
||||
PX4_INFO("- type: P5VDC");
|
||||
break;
|
||||
|
||||
case VOXLPM_CH_TYPE_P12VDC:
|
||||
printf("- type: P12VDC\n");
|
||||
PX4_INFO("- type: P12VDC");
|
||||
break;
|
||||
|
||||
default:
|
||||
printf("- type: UNKOWN\n");
|
||||
PX4_INFO("- type: UNKOWN");
|
||||
break;
|
||||
}
|
||||
|
||||
printf(" - voltage: %9.4f VDC \n", (double)_voltage);
|
||||
printf(" - current: %9.4f ADC \n", (double)_amperage);
|
||||
printf(" - shunt: %9.4f mV, %9.4f mA\n", (double)_vshunt * 1000, (double)_vshuntamps * 1000);
|
||||
printf(" - rsense: %9.6f ohm, cal: %i\n", (double)_rshunt, _cal);
|
||||
printf(" - meas interval: %u us \n", _meas_interval_us);
|
||||
PX4_INFO(" - voltage: %9.4f VDC ", (double)_voltage);
|
||||
PX4_INFO(" - current: %9.4f ADC ", (double)_amperage);
|
||||
PX4_INFO(" - shunt: %9.4f mV, %9.4f mA", (double)_vshunt * 1000, (double)_vshuntamps * 1000);
|
||||
PX4_INFO(" - rsense: %9.6f ohm, cal: %i", (double)_rshunt, _cal);
|
||||
PX4_INFO(" - meas interval: %u us ", _meas_interval_us);
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -246,7 +246,7 @@ private:
|
||||
int measure_ina231();
|
||||
|
||||
bool _initialized;
|
||||
static constexpr unsigned _meas_interval_us{100_ms};
|
||||
static constexpr unsigned _meas_interval_us{20_ms};
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
|
||||
|
||||
@@ -21,6 +21,9 @@ actuator_output:
|
||||
type: enum
|
||||
default: 400
|
||||
values:
|
||||
-8: BDShot150
|
||||
-7: BDShot300
|
||||
-6: BDShot600
|
||||
-5: DShot150
|
||||
-4: DShot300
|
||||
-3: DShot600
|
||||
|
||||
@@ -330,6 +330,10 @@ uint16_t Battery::determineFaults()
|
||||
faults |= (1 << battery_status_s::FAULT_SPIKES);
|
||||
}
|
||||
|
||||
if (PX4_ISFINITE(_temperature_c) && _temperature_c > BAT_TEMP_MAX) {
|
||||
faults |= (1 << battery_status_s::FAULT_OVER_TEMPERATURE);
|
||||
}
|
||||
|
||||
return faults;
|
||||
}
|
||||
|
||||
|
||||
@@ -217,4 +217,10 @@ private:
|
||||
static constexpr float OCV_DEFAULT = 4.2f; // [V] Initial per cell estimate of the open circuit voltage
|
||||
static constexpr float R_COVARIANCE = 0.1f; // Initial per cell covariance of the internal resistance
|
||||
static constexpr float OCV_COVARIANCE = 1.5f; // Initial per cell covariance of the open circuit voltage
|
||||
|
||||
// Temperature [degC] above which an overtemperature fault is declared,
|
||||
// leading to a failsafe warning recommending immediate landing. Note
|
||||
// that depending on the setup this may be measured in/close to the
|
||||
// battery (smart battery) or from a separate power monitor module.
|
||||
static constexpr float BAT_TEMP_MAX = 100.0f;
|
||||
};
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -82,7 +82,7 @@ void EscChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
checkEscStatus(context, reporter, esc_status);
|
||||
reporter.setIsPresent(health_component_t::motors_escs);
|
||||
|
||||
} else if (_param_escs_checks_required.get()
|
||||
} else if (_param_com_arm_chk_escs.get()
|
||||
&& now - _start_time > 5_s) { // Wait a bit after startup to allow esc's to init
|
||||
|
||||
/* EVENT
|
||||
@@ -102,40 +102,37 @@ void EscChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
|
||||
void EscChecks::checkEscStatus(const Context &context, Report &reporter, const esc_status_s &esc_status)
|
||||
{
|
||||
const NavModes required_modes = _param_escs_checks_required.get() ? NavModes::All : NavModes::None;
|
||||
const NavModes required_modes = _param_com_arm_chk_escs.get() ? NavModes::All : NavModes::None;
|
||||
|
||||
if (esc_status.esc_count > 0) {
|
||||
|
||||
// Check if one or more the ESCs are offline
|
||||
char esc_fail_msg[50];
|
||||
esc_fail_msg[0] = '\0';
|
||||
|
||||
int online_bitmask = (1 << esc_status.esc_count) - 1;
|
||||
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; ++i) {
|
||||
const bool mapped = math::isInRange(esc_status.esc[i].actuator_function, actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1,
|
||||
uint8_t(actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1 + actuator_motors_s::NUM_CONTROLS - 1));
|
||||
const bool offline = (esc_status.esc_online_flags & (1 << i)) == 0;
|
||||
|
||||
// Check if one or more the ESCs are offline
|
||||
if (online_bitmask != esc_status.esc_online_flags) {
|
||||
|
||||
for (int index = 0; index < esc_status.esc_count; index++) {
|
||||
if ((esc_status.esc_online_flags & (1 << index)) == 0) {
|
||||
uint8_t motor_index = esc_status.esc[index].actuator_function - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1 + 1;
|
||||
/* EVENT
|
||||
* @description
|
||||
* <profile name="dev">
|
||||
* This check can be configured via <param>COM_ARM_CHK_ESCS</param> parameter.
|
||||
* </profile>
|
||||
*/
|
||||
reporter.healthFailure<uint8_t>(required_modes, health_component_t::motors_escs, events::ID("check_escs_offline"),
|
||||
events::Log::Critical, "ESC {1} offline", motor_index);
|
||||
snprintf(esc_fail_msg + strlen(esc_fail_msg), sizeof(esc_fail_msg) - strlen(esc_fail_msg), "ESC%d ", motor_index);
|
||||
esc_fail_msg[sizeof(esc_fail_msg) - 1] = '\0';
|
||||
}
|
||||
}
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "%soffline. %s\t", esc_fail_msg, context.isArmed() ? "Land now!" : "");
|
||||
if (mapped && offline) {
|
||||
/* EVENT
|
||||
* @description
|
||||
* <profile name="dev">
|
||||
* This check can be configured via <param>COM_ARM_CHK_ESCS</param> parameter.
|
||||
* </profile>
|
||||
*/
|
||||
reporter.healthFailure<uint8_t>(required_modes, health_component_t::motors_escs, events::ID("check_escs_offline"),
|
||||
events::Log::Critical, "ESC {1} offline", i + 1);
|
||||
snprintf(esc_fail_msg + strlen(esc_fail_msg), sizeof(esc_fail_msg) - strlen(esc_fail_msg), "ESC%d ", i + 1);
|
||||
esc_fail_msg[sizeof(esc_fail_msg) - 1] = '\0';
|
||||
}
|
||||
}
|
||||
|
||||
for (int index = 0; index < esc_status.esc_count; index++) {
|
||||
if ((esc_fail_msg[0] != '\0') && reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "%soffline. %s\t", esc_fail_msg, context.isArmed() ? "Land now!" : "");
|
||||
}
|
||||
|
||||
for (int index = 0; index < math::min(esc_status.esc_count, esc_status_s::CONNECTED_ESC_MAX); ++index) {
|
||||
|
||||
if (esc_status.esc[index].failures != 0) {
|
||||
|
||||
|
||||
@@ -54,6 +54,6 @@ private:
|
||||
const hrt_abstime _start_time{hrt_absolute_time()};
|
||||
|
||||
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
|
||||
(ParamBool<px4::params::COM_ARM_CHK_ESCS>) _param_escs_checks_required
|
||||
(ParamBool<px4::params::COM_ARM_CHK_ESCS>) _param_com_arm_chk_escs
|
||||
)
|
||||
};
|
||||
|
||||
@@ -101,7 +101,7 @@ void FailureDetector::publishStatus()
|
||||
failure_detector_status.fd_imbalanced_prop = _failure_detector_status.flags.imbalanced_prop;
|
||||
failure_detector_status.fd_motor = _failure_detector_status.flags.motor;
|
||||
failure_detector_status.imbalanced_prop_metric = _imbalanced_prop_lpf.getState();
|
||||
failure_detector_status.motor_failure_mask = _motor_failure_esc_timed_out_mask | _motor_failure_esc_under_current_mask;
|
||||
failure_detector_status.motor_failure_mask = _motor_failure_mask;
|
||||
failure_detector_status.motor_stop_mask = _failure_injector.getMotorStopMask();
|
||||
failure_detector_status.timestamp = hrt_absolute_time();
|
||||
_failure_detector_status_pub.publish(failure_detector_status);
|
||||
@@ -141,13 +141,13 @@ void FailureDetector::updateAttitudeStatus(const vehicle_status_s &vehicle_statu
|
||||
const bool roll_status = (max_roll > FLT_EPSILON) && (fabsf(roll) > max_roll);
|
||||
const bool pitch_status = (max_pitch > FLT_EPSILON) && (fabsf(pitch) > max_pitch);
|
||||
|
||||
hrt_abstime time_now = hrt_absolute_time();
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
// Update hysteresis
|
||||
_roll_failure_hysteresis.set_hysteresis_time_from(false, (hrt_abstime)(1_s * _param_fd_fail_r_ttri.get()));
|
||||
_pitch_failure_hysteresis.set_hysteresis_time_from(false, (hrt_abstime)(1_s * _param_fd_fail_p_ttri.get()));
|
||||
_roll_failure_hysteresis.set_state_and_update(roll_status, time_now);
|
||||
_pitch_failure_hysteresis.set_state_and_update(pitch_status, time_now);
|
||||
_roll_failure_hysteresis.set_state_and_update(roll_status, now);
|
||||
_pitch_failure_hysteresis.set_state_and_update(pitch_status, now);
|
||||
|
||||
// Update status
|
||||
_failure_detector_status.flags.roll = _roll_failure_hysteresis.get_state();
|
||||
@@ -164,11 +164,9 @@ void FailureDetector::updateExternalAtsStatus()
|
||||
uint32_t pulse_width = pwm_input.pulse_width;
|
||||
bool ats_trigger_status = (pulse_width >= (uint32_t)_param_fd_ext_ats_trig.get()) && (pulse_width < 3_ms);
|
||||
|
||||
hrt_abstime time_now = hrt_absolute_time();
|
||||
|
||||
// Update hysteresis
|
||||
_ext_ats_failure_hysteresis.set_hysteresis_time_from(false, 100_ms); // 5 consecutive pulses at 50hz
|
||||
_ext_ats_failure_hysteresis.set_state_and_update(ats_trigger_status, time_now);
|
||||
_ext_ats_failure_hysteresis.set_state_and_update(ats_trigger_status, hrt_absolute_time());
|
||||
|
||||
_failure_detector_status.flags.ext = _ext_ats_failure_hysteresis.get_state();
|
||||
}
|
||||
@@ -176,7 +174,7 @@ void FailureDetector::updateExternalAtsStatus()
|
||||
|
||||
void FailureDetector::updateEscsStatus(const vehicle_status_s &vehicle_status, const esc_status_s &esc_status)
|
||||
{
|
||||
hrt_abstime time_now = hrt_absolute_time();
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
if (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
||||
const int limited_esc_count = math::min(esc_status.esc_count, esc_status_s::CONNECTED_ESC_MAX);
|
||||
@@ -190,7 +188,7 @@ void FailureDetector::updateEscsStatus(const vehicle_status_s &vehicle_status, c
|
||||
}
|
||||
|
||||
_esc_failure_hysteresis.set_hysteresis_time_from(false, 300_ms);
|
||||
_esc_failure_hysteresis.set_state_and_update(is_esc_failure, time_now);
|
||||
_esc_failure_hysteresis.set_state_and_update(is_esc_failure, now);
|
||||
|
||||
if (_esc_failure_hysteresis.get_state()) {
|
||||
_failure_detector_status.flags.arm_escs = true;
|
||||
@@ -198,7 +196,7 @@ void FailureDetector::updateEscsStatus(const vehicle_status_s &vehicle_status, c
|
||||
|
||||
} else {
|
||||
// reset ESC bitfield
|
||||
_esc_failure_hysteresis.set_state_and_update(false, time_now);
|
||||
_esc_failure_hysteresis.set_state_and_update(false, now);
|
||||
_failure_detector_status.flags.arm_escs = false;
|
||||
}
|
||||
}
|
||||
@@ -263,110 +261,79 @@ void FailureDetector::updateImbalancedPropStatus()
|
||||
|
||||
void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, const esc_status_s &esc_status)
|
||||
{
|
||||
// What need to be checked:
|
||||
//
|
||||
// 1. ESC telemetry disappears completely -> dead ESC or power loss on that ESC
|
||||
// 2. ESC failures like overvoltage, overcurrent etc. But DShot driver for example is not populating the field 'esc_report.failures'
|
||||
// 3. Motor current too low. Compare drawn motor current to expected value from a parameter
|
||||
// -- ESC voltage does not really make sense and is highly dependent on the setup
|
||||
// 1. Telemetry times out -> communication or power lost on that ESC
|
||||
// 2. Too low current draw compared to commanded thrust
|
||||
// Overvoltage, overcurrent do not have checks yet esc_report.failures are handled separately
|
||||
|
||||
// First wait for some ESC telemetry that has the required fields. Before that happens, don't check this ESC
|
||||
// Then check
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
// Only check while armed
|
||||
if (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
const int limited_esc_count = math::min(esc_status.esc_count, esc_status_s::CONNECTED_ESC_MAX);
|
||||
|
||||
actuator_motors_s actuator_motors{};
|
||||
_actuator_motors_sub.copy(&actuator_motors);
|
||||
|
||||
// Check individual ESC reports
|
||||
for (int esc_status_idx = 0; esc_status_idx < limited_esc_count; esc_status_idx++) {
|
||||
|
||||
const esc_report_s &cur_esc_report = esc_status.esc[esc_status_idx];
|
||||
|
||||
for (uint8_t i = 0; i < esc_status_s::CONNECTED_ESC_MAX; ++i) {
|
||||
// Map the esc status index to the actuator function index
|
||||
const unsigned i_esc = cur_esc_report.actuator_function - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1;
|
||||
const uint8_t actuator_function_index =
|
||||
esc_status.esc[i].actuator_function - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1;
|
||||
|
||||
if (i_esc >= actuator_motors_s::NUM_CONTROLS) {
|
||||
if (actuator_function_index >= actuator_motors_s::NUM_CONTROLS) {
|
||||
continue; // Invalid mapping
|
||||
}
|
||||
|
||||
const bool timeout = now > esc_status.esc[i].timestamp + 300_ms;
|
||||
const float current = esc_status.esc[i].esc_current;
|
||||
|
||||
// First wait for ESC telemetry reporting non-zero current. Before that happens, don't check it.
|
||||
if (current > FLT_EPSILON) {
|
||||
_esc_has_reported_current[i] = true;
|
||||
}
|
||||
|
||||
if (!_esc_has_reported_current[i]) {
|
||||
continue;
|
||||
}
|
||||
|
||||
// Check if ESC telemetry was available and valid at some point. This is a prerequisite for the failure detection.
|
||||
if (!(_motor_failure_esc_valid_current_mask & (1 << i_esc)) && cur_esc_report.esc_current > 0.0f) {
|
||||
_motor_failure_esc_valid_current_mask |= (1 << i_esc);
|
||||
_motor_failure_mask &= ~(1u << actuator_function_index); // Reset bit in mask to accumulate failures again
|
||||
_motor_failure_mask |= (static_cast<uint16_t>(timeout) << actuator_function_index); // Telemetry timeout
|
||||
|
||||
// Current limits
|
||||
float thrust = 0.f;
|
||||
|
||||
if (PX4_ISFINITE(actuator_motors.control[actuator_function_index])) {
|
||||
// Normalized motor thrust commands before thrust model factor is applied, NAN means motor is turned off -> 0 thrust
|
||||
thrust = fabsf(actuator_motors.control[actuator_function_index]);
|
||||
}
|
||||
|
||||
// Check for telemetry timeout
|
||||
const bool esc_timed_out = now > cur_esc_report.timestamp + 300_ms;
|
||||
const bool esc_was_valid = _motor_failure_esc_valid_current_mask & (1 << i_esc);
|
||||
const bool esc_timeout_currently_flagged = _motor_failure_esc_timed_out_mask & (1 << i_esc);
|
||||
bool thrust_above_threshold = thrust > _param_fd_act_mot_thr.get();
|
||||
bool current_too_low = current < (thrust * _param_fd_act_mot_c2t.get()) - _param_fd_act_low_off.get();
|
||||
bool current_too_high = current > (thrust * _param_fd_act_mot_c2t.get()) + _param_fd_act_high_off.get();
|
||||
|
||||
if (esc_was_valid && esc_timed_out && !esc_timeout_currently_flagged) {
|
||||
// Set flag
|
||||
_motor_failure_esc_timed_out_mask |= (1 << i_esc);
|
||||
_esc_undercurrent_hysteresis[i].set_hysteresis_time_from(false, _param_fd_act_mot_tout.get() * 1_ms);
|
||||
_esc_overcurrent_hysteresis[i].set_hysteresis_time_from(false, _param_fd_act_mot_tout.get() * 1_ms);
|
||||
|
||||
} else if (!esc_timed_out && esc_timeout_currently_flagged) {
|
||||
// Reset flag
|
||||
_motor_failure_esc_timed_out_mask &= ~(1 << i_esc);
|
||||
if (!_esc_undercurrent_hysteresis[i].get_state()) {
|
||||
// Do not clear mid operation because a reaction could be to stop the motor and that would be conidered healthy again
|
||||
_esc_undercurrent_hysteresis[i].set_state_and_update(thrust_above_threshold && current_too_low && !timeout, now);
|
||||
}
|
||||
|
||||
// Check if ESC current is too low
|
||||
if (cur_esc_report.esc_current > FLT_EPSILON) {
|
||||
_motor_failure_esc_has_current[i_esc] = true;
|
||||
if (!_esc_overcurrent_hysteresis[i].get_state()) {
|
||||
// Do not clear mid operation because a reaction could be to stop the motor and that would be conidered healthy again
|
||||
_esc_overcurrent_hysteresis[i].set_state_and_update(current_too_high && !timeout, now);
|
||||
}
|
||||
|
||||
if (_motor_failure_esc_has_current[i_esc]) {
|
||||
float esc_throttle = 0.f;
|
||||
|
||||
if (PX4_ISFINITE(actuator_motors.control[i_esc])) {
|
||||
esc_throttle = fabsf(actuator_motors.control[i_esc]);
|
||||
}
|
||||
|
||||
const bool throttle_above_threshold = esc_throttle > _param_fd_act_mot_thr.get();
|
||||
const bool current_too_low = cur_esc_report.esc_current < esc_throttle *
|
||||
_param_fd_act_mot_c2t.get();
|
||||
|
||||
if (throttle_above_threshold && current_too_low && !esc_timed_out) {
|
||||
if (_motor_failure_undercurrent_start_time[i_esc] == 0) {
|
||||
_motor_failure_undercurrent_start_time[i_esc] = now;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (_motor_failure_undercurrent_start_time[i_esc] != 0) {
|
||||
_motor_failure_undercurrent_start_time[i_esc] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (_motor_failure_undercurrent_start_time[i_esc] != 0
|
||||
&& now > (_motor_failure_undercurrent_start_time[i_esc] + (_param_fd_act_mot_tout.get() * 1_ms))
|
||||
&& (_motor_failure_esc_under_current_mask & (1 << i_esc)) == 0) {
|
||||
// Set flag
|
||||
_motor_failure_esc_under_current_mask |= (1 << i_esc);
|
||||
|
||||
} // else: this flag is never cleared, as the motor is stopped, so throttle < threshold
|
||||
}
|
||||
_motor_failure_mask |= (static_cast<uint16_t>(_esc_undercurrent_hysteresis[i].get_state()) << actuator_function_index);
|
||||
_motor_failure_mask |= (static_cast<uint16_t>(_esc_overcurrent_hysteresis[i].get_state()) << actuator_function_index);
|
||||
}
|
||||
|
||||
bool critical_esc_failure = (_motor_failure_esc_timed_out_mask != 0 || _motor_failure_esc_under_current_mask != 0);
|
||||
|
||||
if (critical_esc_failure && !(_failure_detector_status.flags.motor)) {
|
||||
// Add motor failure flag to bitfield
|
||||
_failure_detector_status.flags.motor = true;
|
||||
|
||||
} else if (!critical_esc_failure && _failure_detector_status.flags.motor) {
|
||||
// Reset motor failure flag
|
||||
_failure_detector_status.flags.motor = false;
|
||||
}
|
||||
_failure_detector_status.flags.motor = (_motor_failure_mask != 0u);
|
||||
|
||||
} else { // Disarmed
|
||||
// reset ESC bitfield
|
||||
for (int i_esc = 0; i_esc < actuator_motors_s::NUM_CONTROLS; i_esc++) {
|
||||
_motor_failure_undercurrent_start_time[i_esc] = 0;
|
||||
for (uint8_t i = 0; i < esc_status_s::CONNECTED_ESC_MAX; ++i) {
|
||||
_esc_undercurrent_hysteresis[i].set_state_and_update(false, now);
|
||||
_esc_overcurrent_hysteresis[i].set_state_and_update(false, now);
|
||||
}
|
||||
|
||||
_motor_failure_esc_under_current_mask = 0;
|
||||
_failure_detector_status.flags.motor = false;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -111,11 +111,10 @@ private:
|
||||
hrt_abstime _imu_status_timestamp_prev{0};
|
||||
|
||||
// Motor failure check
|
||||
uint8_t _motor_failure_esc_valid_current_mask{}; // ESC 1-8, true if ESC telemetry was valid at some point
|
||||
uint8_t _motor_failure_esc_timed_out_mask{}; // ESC telemetry no longer available -> failure
|
||||
uint8_t _motor_failure_esc_under_current_mask{}; // ESC drawing too little current -> failure
|
||||
bool _motor_failure_esc_has_current[actuator_motors_s::NUM_CONTROLS] {false}; // true if some ESC had non-zero current (some don't support it)
|
||||
hrt_abstime _motor_failure_undercurrent_start_time[actuator_motors_s::NUM_CONTROLS] {};
|
||||
bool _esc_has_reported_current[esc_status_s::CONNECTED_ESC_MAX] {}; // true if ESC reported non-zero current before (some never report any)
|
||||
systemlib::Hysteresis _esc_undercurrent_hysteresis[esc_status_s::CONNECTED_ESC_MAX];
|
||||
systemlib::Hysteresis _esc_overcurrent_hysteresis[esc_status_s::CONNECTED_ESC_MAX];
|
||||
uint16_t _motor_failure_mask = 0; // actuator function indexed
|
||||
|
||||
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
|
||||
uORB::Subscription _esc_status_sub{ORB_ID(esc_status)}; // TODO: multi-instance
|
||||
@@ -142,6 +141,8 @@ private:
|
||||
(ParamBool<px4::params::FD_ACT_EN>) _param_fd_act_en,
|
||||
(ParamFloat<px4::params::FD_ACT_MOT_THR>) _param_fd_act_mot_thr,
|
||||
(ParamFloat<px4::params::FD_ACT_MOT_C2T>) _param_fd_act_mot_c2t,
|
||||
(ParamInt<px4::params::FD_ACT_MOT_TOUT>) _param_fd_act_mot_tout
|
||||
(ParamInt<px4::params::FD_ACT_MOT_TOUT>) _param_fd_act_mot_tout,
|
||||
(ParamFloat<px4::params::FD_ACT_LOW_OFF>) _param_fd_act_low_off,
|
||||
(ParamFloat<px4::params::FD_ACT_HIGH_OFF>) _param_fd_act_high_off
|
||||
)
|
||||
};
|
||||
|
||||
@@ -169,12 +169,13 @@ PARAM_DEFINE_INT32(FD_IMB_PROP_THR, 30);
|
||||
*
|
||||
* @group Failure Detector
|
||||
*/
|
||||
PARAM_DEFINE_INT32(FD_ACT_EN, 1);
|
||||
PARAM_DEFINE_INT32(FD_ACT_EN, 0);
|
||||
|
||||
/**
|
||||
* Motor Failure Throttle Threshold
|
||||
* Motor Failure Thrust Threshold
|
||||
*
|
||||
* Motor failure triggers only above this throttle value.
|
||||
* Failure detection per motor only triggers above this thrust value.
|
||||
* Set to 1 to disable the detection.
|
||||
*
|
||||
* @group Failure Detector
|
||||
* @unit norm
|
||||
@@ -186,9 +187,11 @@ PARAM_DEFINE_INT32(FD_ACT_EN, 1);
|
||||
PARAM_DEFINE_FLOAT(FD_ACT_MOT_THR, 0.2f);
|
||||
|
||||
/**
|
||||
* Motor Failure Current/Throttle Threshold
|
||||
* Motor Failure Current/Throttle Scale
|
||||
*
|
||||
* Motor failure triggers only below this current value
|
||||
* Determines the slope between expected steady state current and linearized, normalized thrust command.
|
||||
* E.g. FD_ACT_MOT_C2T A represents the expected steady state current at 100%.
|
||||
* FD_ACT_LOW_OFF and FD_ACT_HIGH_OFF offset the threshold from that slope.
|
||||
*
|
||||
* @group Failure Detector
|
||||
* @min 0.0
|
||||
@@ -197,13 +200,12 @@ PARAM_DEFINE_FLOAT(FD_ACT_MOT_THR, 0.2f);
|
||||
* @decimal 2
|
||||
* @increment 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FD_ACT_MOT_C2T, 2.0f);
|
||||
PARAM_DEFINE_FLOAT(FD_ACT_MOT_C2T, 35.f);
|
||||
|
||||
/**
|
||||
* Motor Failure Time Threshold
|
||||
* Motor Failure Hysteresis Time
|
||||
*
|
||||
* Motor failure triggers only if the throttle threshold and the
|
||||
* current to throttle threshold are violated for this time.
|
||||
* Motor failure only triggers after current thresholds are exceeded for this time.
|
||||
*
|
||||
* @group Failure Detector
|
||||
* @unit ms
|
||||
@@ -211,4 +213,32 @@ PARAM_DEFINE_FLOAT(FD_ACT_MOT_C2T, 2.0f);
|
||||
* @max 10000
|
||||
* @increment 100
|
||||
*/
|
||||
PARAM_DEFINE_INT32(FD_ACT_MOT_TOUT, 100);
|
||||
PARAM_DEFINE_INT32(FD_ACT_MOT_TOUT, 1000);
|
||||
|
||||
/**
|
||||
* Undercurrent motor failure limit offset
|
||||
*
|
||||
* threshold = FD_ACT_MOT_C2T * thrust - FD_ACT_LOW_OFF
|
||||
*
|
||||
* @group Failure Detector
|
||||
* @min 0
|
||||
* @max 30
|
||||
* @unit A
|
||||
* @decimal 2
|
||||
* @increment 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FD_ACT_LOW_OFF, 10.f);
|
||||
|
||||
/**
|
||||
* Overcurrent motor failure limit offset
|
||||
*
|
||||
* threshold = FD_ACT_MOT_C2T * thrust + FD_ACT_HIGH_OFF
|
||||
*
|
||||
* @group Failure Detector
|
||||
* @min 0
|
||||
* @max 30
|
||||
* @unit A
|
||||
* @decimal 2
|
||||
* @increment 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FD_ACT_HIGH_OFF, 10.f);
|
||||
|
||||
@@ -63,7 +63,11 @@ __BEGIN_DECLS
|
||||
__EXPORT int dataman_main(int argc, char *argv[]);
|
||||
__END_DECLS
|
||||
|
||||
#ifdef CONFIG_FS_LITTLEFS
|
||||
static constexpr int TASK_STACK_SIZE = 2000; /* littlefs needs more stack */
|
||||
#else
|
||||
static constexpr int TASK_STACK_SIZE = 1420;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
/* Private File based Operations */
|
||||
|
||||
@@ -49,6 +49,11 @@ bool GnssChecks::run(const gnssSample &gnss, uint64_t time_us)
|
||||
|
||||
bool passed = false;
|
||||
|
||||
// Run strict checks while not flying yet
|
||||
if (!_control_status.flags.in_air) {
|
||||
_initial_checks_passed = false;
|
||||
}
|
||||
|
||||
if (_initial_checks_passed) {
|
||||
if (runSimplifiedChecks(gnss)) {
|
||||
_time_last_pass_us = time_us;
|
||||
|
||||
@@ -190,9 +190,6 @@ public:
|
||||
// return true if the attitude is usable
|
||||
bool attitude_valid() const { return _control_status.flags.tilt_align; }
|
||||
|
||||
// get vehicle landed status data
|
||||
bool get_in_air_status() const { return _control_status.flags.in_air; }
|
||||
|
||||
#if defined(CONFIG_EKF2_WIND)
|
||||
bool get_wind_status() const { return _control_status.flags.wind || _external_wind_init; }
|
||||
#endif // CONFIG_EKF2_WIND
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user