Skip to content
Merged
Show file tree
Hide file tree
Changes from 74 commits
Commits
Show all changes
217 commits
Select commit Hold shift + click to select a range
b93cb96
rebased
dakejahl Nov 20, 2025
74da73e
fix frame quantization
dakejahl Nov 21, 2025
844b5ad
add no_data counter
dakejahl Nov 21, 2025
a63f180
increase telem processing delay from 3 to 5 seconds
dakejahl Nov 22, 2025
316c0c1
adaptive gcr bit width tracking
dakejahl Nov 22, 2025
bc89140
cleaned up
dakejahl Nov 22, 2025
9761cb3
improve dshot status output
dakejahl Nov 24, 2025
1d576c0
added am32_eeprom to mavlink
dakejahl Nov 24, 2025
bd4ac2a
added mavlink submodule
dakejahl Nov 24, 2025
5c7e33d
fixup mavlink, enable development on ARK FPV
dakejahl Nov 24, 2025
55cdb4d
it's working
dakejahl Nov 25, 2025
b4e69e9
update mavlink
dakejahl Nov 27, 2025
22ac085
update mavlink
dakejahl Nov 27, 2025
e674459
rename to ESC_EEPROM and fix up logic for 192 length
dakejahl Nov 28, 2025
c6c8cdd
mavlink submodule
dakejahl Dec 17, 2025
3b9ea30
clean up naming
dakejahl Dec 26, 2025
46cecf6
multi timer, first pass
dakejahl Dec 26, 2025
d1d5417
fix issues found during review, clean up
dakejahl Dec 26, 2025
4b3cd1e
fix names and variables and remove dead code
dakejahl Dec 26, 2025
22587b0
bdshot per channel, use PWM_TIM param for BDSHOT instead of single pa…
dakejahl Dec 27, 2025
f6eeacf
temporarily comment out dshot re-init
dakejahl Jan 5, 2026
3c8a652
before claude
dakejahl Jan 8, 2026
8ab112b
after claudes fixes
dakejahl Jan 8, 2026
bf78377
fix esc online mask ordering, fix bdshot channels ready check, improv…
dakejahl Jan 9, 2026
4ee3d27
sequential dshot burst/capture timer triggering, it works!
dakejahl Jan 9, 2026
72cd09b
fix handling MAV_CMD_CONFIGURE_ACTUATOR -1000
dakejahl Jan 10, 2026
2d7b3a8
bdshot_analyzer.py for saleae timign analysis
dakejahl Jan 13, 2026
597611e
code simplifier
dakejahl Jan 13, 2026
b5e9457
remove bdshot_timing_analyzer_spec.md
dakejahl Jan 14, 2026
24d7cd4
board: ark_fpv: add rc.board_airframes to reduce flash
dakejahl Jan 14, 2026
458c775
fix ifdef, adjust esc isInRange check
dakejahl Jan 14, 2026
c434ef1
fix build and rename _param_escs_checks_required
dakejahl Jan 14, 2026
9ad690d
fix rpm overflow, change type to int32
dakejahl Jan 14, 2026
6bc0e0c
dshot: imxrt: fix unsigned to uint8_t in dshot_motor_data_set
dakejahl Jan 14, 2026
7edc606
don't use DSHOT_TEL_CFG directly in code since it is autogenerated on…
dakejahl Jan 15, 2026
8847c3c
dshot: trigger timers at the same time, with 10us delay between burst…
dakejahl Jan 21, 2026
4d09521
make format
dakejahl Jan 21, 2026
e835394
mavlink: fixup ifdefs around ESC_EEPROM
julianoes Jan 21, 2026
b1585a7
Update platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c
dakejahl Jan 26, 2026
89f1410
Update platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c
dakejahl Jan 26, 2026
44f62fd
rename perf counters, skip burst delay on last channel
dakejahl Jan 26, 2026
c9a8f37
remove TODO
dakejahl Jan 26, 2026
bbbac3b
remove debug mavlink code
dakejahl Jan 26, 2026
5cde036
fix date
dakejahl Jan 26, 2026
d72542a
replace eeprom struct with opaque buffer
dakejahl Jan 26, 2026
0c51b25
dshot: support timer channels without DMA capture
julianoes Jan 27, 2026
3ef8b10
dshot: improve status output
julianoes Jan 27, 2026
b26b3ac
boards: fixup timers and DMA for KakuteH7-Wing
julianoes Jan 27, 2026
47bb143
adjust debug message
dakejahl Jan 28, 2026
6f8ba00
dshot: fix bug preventing writing settings
dakejahl Jan 28, 2026
ac5fba4
imxrt: add up_bdshot_channel_capture_supported
dakejahl Jan 28, 2026
a9f5e5d
remove extra newlines
dakejahl Jan 28, 2026
4f70ed3
dshot: fix optarg list
dakejahl Jan 28, 2026
b05c772
dshot: module.yaml: esc_type default 0
dakejahl Jan 28, 2026
130ec77
boards: don't use the word capture
julianoes Jan 30, 2026
81a8a88
msg/mavlink: report up to 12 motors
julianoes Feb 2, 2026
53a4a87
dshot: enable up to 16 DShot channels
julianoes Feb 2, 2026
b1b3a69
Update to UORB docs according to standard
hamishwillee Feb 3, 2026
408a773
ARKV6X fix flash overflow
AlexKlimaj Feb 4, 2026
f6a0ed5
dshot: remove redundant static_assert for ESC_MAX channels
AlexKlimaj Feb 4, 2026
b9f6e35
dshot: just publish at 200 Hz
julianoes Feb 6, 2026
7b09845
dshot: add EDT data to status
julianoes Feb 6, 2026
7e2361a
dshot: fix EDT request
julianoes Feb 6, 2026
ae5b191
bump mavlink
dakejahl Feb 10, 2026
4cfda1f
Merge branch 'main' into dev/dshot_stuff2
dakejahl Feb 10, 2026
f78ce5b
clean up
dakejahl Feb 10, 2026
e5068e1
cleanup print_status, rename perf counters
dakejahl Feb 10, 2026
789bdbd
dshot: replace MOT_POLE_COUNT with per-motor parameters DSHOT_MOT_POL
dakejahl Feb 11, 2026
d68cbad
ark_fpv: add 2106_albatross to airframe list
dakejahl Feb 17, 2026
5be7943
ark boards: change GPIO_FMU output init from PULLDOWN to PULLUP
dakejahl Feb 19, 2026
06e6b51
Merge branch 'jake/ark_outputs_pullup' into dev/dshot_stuff2
dakejahl Feb 19, 2026
6126c01
remove fmu output gpio init
dakejahl Feb 19, 2026
32a880d
Merge branch 'jake/ark_outputs_pullup' into dev/dshot_stuff2
dakejahl Feb 19, 2026
c1586bc
Merge branch 'main' into dev/dshot_stuff2
dakejahl Feb 19, 2026
f9798f6
Merge branch 'main' into dev/dshot_stuff2
dakejahl Feb 24, 2026
6397c11
EscReport.msg: fix motor_temperature comment syntax
dakejahl Feb 24, 2026
c464dc5
fix syntax
dakejahl Feb 24, 2026
77c32fe
Merge branch 'main' into dev/dshot_stuff2
dakejahl Feb 24, 2026
e37c4cf
ark_fpv: mavlink-dev.px4board
dakejahl Feb 24, 2026
5cf7411
EscReport: remove unimplemented esc_cmdcount
dakejahl Feb 24, 2026
a88db5b
logged_topics.cpp: revert changes
dakejahl Feb 24, 2026
6fb29ae
remove Tools/bdshot_analyzer.py
dakejahl Feb 24, 2026
c2e5d09
ark_fmu-v6x: mavlink-dev.px4board
dakejahl Feb 25, 2026
1c577c4
ark_pi6x: mavlink-dev.px4board
dakejahl Feb 25, 2026
5eb1cba
add docs
dakejahl Feb 26, 2026
4d80877
Update docs/en/esc/ark_4in1_esc.md
dakejahl Feb 26, 2026
86e9eb8
Update docs/en/peripherals/dshot.md
dakejahl Feb 26, 2026
98932f5
Update docs/en/peripherals/dshot.md
dakejahl Feb 26, 2026
74e21bb
Update docs/en/peripherals/dshot.md
dakejahl Feb 26, 2026
6118dfc
docs: dshot: add back 1.16 badge
dakejahl Feb 26, 2026
34eae75
docs: dshot: add links to dshot/bdshot spec
dakejahl Feb 26, 2026
1fc67ff
Merge branch 'main' into dev/dshot_stuff2
dakejahl Mar 2, 2026
c919a83
Merge branch 'main' into dev/dshot_stuff2
AlexKlimaj Mar 4, 2026
bf772e2
Merge branch 'main' into dev/dshot_stuff2
dakejahl Mar 4, 2026
cedc4f0
Merge branch 'main' into dev/dshot_stuff2
dakejahl Mar 5, 2026
c47dbfb
fix(dshot): widen motor masks to uint16_t for 12 ESC support
dakejahl Mar 10, 2026
bb3f95a
fix(dshot): bounds-check esc_index before shift operations
dakejahl Mar 10, 2026
069eff3
fix(dshot): use unit16 for voltage/current/erpm
dakejahl Mar 10, 2026
46093fe
fix(dshot): translate REQUEST_MESSAGE to ESC_REQUEST_EEPROM in mavlin…
dakejahl Mar 10, 2026
7c142b4
fix(format): make format
dakejahl Mar 10, 2026
396c90c
fix(dshot): volatile keyword to _bdshot_cycle_complete
dakejahl Mar 10, 2026
6573fe6
fix(dshot): added TODO
dakejahl Mar 10, 2026
f2e7fe1
fix(dshot): typo
dakejahl Mar 10, 2026
508c4a8
fix(dshot): clamp command response bytes to prevent buffer overflow
dakejahl Mar 10, 2026
2dccba9
fix(dshot): bounds check timer channel
dakejahl Mar 10, 2026
9cc0a82
refactor(dshot): replace timer config magic numbers with named constants
dakejahl Mar 10, 2026
519e1bc
fix(dshot): warn on mixed DShot frequencies across timer groups
dakejahl Mar 10, 2026
b27699b
style(dshot): remove commented-out code
dakejahl Mar 10, 2026
d85a059
fix(dshot): fix typos in messages, docs, and comments
dakejahl Mar 10, 2026
9a36d24
fix(mavlink): only copy actual EEPROM data length in ESC_EEPROM stream
dakejahl Mar 10, 2026
2fde11a
fix(mavlink): guard esc_eeprom_write include and member behind ifdef
dakejahl Mar 10, 2026
7a1464e
refactor(dshot): rename bdshot_success perf counter to bdshot_recv
dakejahl Mar 10, 2026
19a5faa
fix(format): formatting
dakejahl Mar 10, 2026
818992c
fix(ark/fpv): revert bootloader
dakejahl Mar 10, 2026
e65bcca
fix(ark/v6x): revert .px4board changes
dakejahl Mar 10, 2026
67ac464
fix(uavcan/actuators): bump uint8 to uint16 for check_escs_status() r…
dakejahl Mar 11, 2026
f4b4777
fix(dshot): use EscData.source field
dakejahl Mar 11, 2026
26e10e2
fix(dshot): specify static variables
dakejahl Mar 11, 2026
ef5e550
fix(dshot): count_set_bits() return type uint32
dakejahl Mar 11, 2026
c4aecf4
fix(param_translation): translate MOT_POLE_COUNT to DSHOT_MOT_POL{i}
dakejahl Mar 11, 2026
1ac876c
fix(dshot): change print INFO to DEBUG
dakejahl Mar 11, 2026
c8e51e8
fix(dshot): change bool 0 to false
dakejahl Mar 11, 2026
2b3434c
chore(dshot): update copyright year
dakejahl Mar 11, 2026
dd6d769
chore(dshot): clean up DSHOT_MAXIMUM_CHANNELS usage
dakejahl Mar 11, 2026
237b0da
fix(dshot): fix mask mapping
dakejahl Mar 12, 2026
d663a24
fix(dshot): use motor_index for error rate tracking, cast esc.current…
dakejahl Mar 12, 2026
d23abea
revert(dshot): b9f6e35a43f123e293bba5b0e48d05d0bf2da555#diff-ee11cd0d…
dakejahl Mar 12, 2026
b615b1c
fix(dshot): unsigned type
dakejahl Mar 12, 2026
78b086b
fix(dshot): PX4_ERR on command response overflow
dakejahl Mar 12, 2026
b3fca07
fix(dshot): cleanup
dakejahl Mar 12, 2026
014ee2c
chore(dshot): rename
dakejahl Mar 12, 2026
a386fd8
fix(mavlink): use PX4_DEBUG
dakejahl Mar 12, 2026
1cec80f
fix(dshot): fail on command response overflow
dakejahl Mar 12, 2026
b87353f
fix(dshot): constrain pole_count to 2 to avoid divide by zero
dakejahl Mar 12, 2026
05d0d5c
fix(dshot): use CONNECTED_ESC_MAX for param handle array length
dakejahl Mar 12, 2026
591def5
fix(dshot): check channel value before array indexing
dakejahl Mar 12, 2026
f09f18f
fix(dshot): init bdshot_channel_mask to zero
dakejahl Mar 12, 2026
12ba983
fix(dshot): return sentinel from output_channel_from_timer_channel on…
dakejahl Mar 12, 2026
6f3b085
Revert "chore(dshot): rename"
dakejahl Mar 12, 2026
4e16907
fix(dshot/nxp): bounds check on up_bdshot_num_errors()
dakejahl Mar 12, 2026
bb01f56
fix(dshot): remove dead code
dakejahl Mar 12, 2026
112c79f
fix(dshot): fix remaining mask mapping actuator->motor ordering issues
dakejahl Mar 12, 2026
fe6274b
refactor(dshot): simplify function to return void
dakejahl Mar 12, 2026
0843a8f
fix(dshot): reset command response state on overflow
dakejahl Mar 12, 2026
1c93b10
fix(dshot): fix actuator/motor index inconsistencies
dakejahl Mar 12, 2026
5bb82d6
fix(msg): remove extra param fields in vehicle cmd
dakejahl Mar 12, 2026
93904c0
refactor(dshot): use lroundf() for float-to-int param conversion
dakejahl Mar 12, 2026
19c6637
fix(dshot): zero init array
dakejahl Mar 12, 2026
11bf15f
fix(dshot): adjust max command response from 192 to 49
dakejahl Mar 12, 2026
81ae5b6
Merge branch 'main' into dev/dshot_stuff2
dakejahl Mar 12, 2026
96437b6
fix(dshot): fix PRIx32 formatting
dakejahl Mar 12, 2026
4798dd2
chore(msg): fix whitespace
dakejahl Mar 12, 2026
ea8c3a9
fix(dshot): revert -DDEBUG_BUILD
dakejahl Mar 12, 2026
e102c9c
fix(params): fix PRId32 format specifier in param_translation
dakejahl Mar 12, 2026
d07ec69
fix(mavlink): copy const vehicle_command before modifying
dakejahl Mar 12, 2026
d6e2111
fix(logger): reduce esc_status logging to 10Hz
dakejahl Mar 12, 2026
fb985ad
fix(dshot): don't run capture callback during init
dakejahl Mar 13, 2026
86cde62
fix(dshot): move param_get out of hot path, cache pole_count params
dakejahl Mar 13, 2026
1f8a8c1
fix(dshot/serial_telem): reduce CPU polling on read()
dakejahl Mar 13, 2026
cf829b4
fix(dshot): reduce bdshot ISR overhead
dakejahl Mar 13, 2026
e5ad0b6
fix(dshot): start telemetry index search from current position
dakejahl Mar 13, 2026
136827e
fix(bdshot): don't clear _bdshot_processed for non-capture channels
dakejahl Mar 13, 2026
f67a195
fix(dshot): minor fixes
dakejahl Mar 13, 2026
070d630
fix(dshot): ensure both telemetry paths always run
dakejahl Mar 13, 2026
d4e7b43
fix(dshot): fix OOB access in NXP up_bdshot_num_errors()
dakejahl Mar 13, 2026
64d6cba
fix(dshot): return 0 for invalid channels in NXP up_bdshot_channel_on…
dakejahl Mar 13, 2026
f740134
fix(dshot): prevent deadlock on DMA alloc failure
dakejahl Mar 13, 2026
eb2913d
fix(dshot): use motor-index domain in serial telemetry round-robin
dakejahl Mar 13, 2026
ba0a362
fix(dshot): reset frame position on new telemetry request
dakejahl Mar 13, 2026
3a800e4
fix(dshot): count all processed channels in NXP num_channels_ready()
dakejahl Mar 13, 2026
4a55fa0
fix(dshot): restore pin mode and end perf on capture DMA alloc failure
dakejahl Mar 13, 2026
445c70d
fix(dshot): add volatile to ISR-written telemetry data
dakejahl Mar 13, 2026
0aab523
fix(mavlink): clamp ESC_EEPROM msg.length to actual bytes copied
dakejahl Mar 13, 2026
e07fa08
fix(dshot): silence spurious warning for default ESC type Unknown
dakejahl Mar 13, 2026
2095784
fix(dshot): reset command response state when handler is null
dakejahl Mar 13, 2026
eab36a7
fix(mavlink): fix ESC_INFO for 12-ESC support
dakejahl Mar 13, 2026
1a28268
fix(mavlink): read all ESC_STATUS subscribers when aggregating ESC data
dakejahl Mar 13, 2026
5783c83
fix(dshot): remove dead code and fix NXP init return value
dakejahl Mar 13, 2026
3b91bf8
fix(mavlink): always emit ESC messages for all known slots
dakejahl Mar 13, 2026
ff987fe
fix(mavlink): defer ESC_EEPROM request ACK to DShot driver
dakejahl Mar 13, 2026
eb2ea63
fix(dshot): add missing cstdint include in ESCSettingsInterface.h
dakejahl Mar 13, 2026
bc0b0e6
fix(dshot): skip ESC_INFO request when ESC type is Unknown
dakejahl Mar 13, 2026
b727cc9
fix(dshot): compute esc_online_flags per-motor instead of globally
dakejahl Mar 13, 2026
c2180c5
fix(dshot): add bounds check to NXP up_bdshot_get_erpm()
dakejahl Mar 13, 2026
94eaef4
fix(dshot): compare telemetry mask against motor mask, not output mask
dakejahl Mar 13, 2026
1f0c4ae
fix(mavlink): ACK REQUEST_MESSAGE not internal ESC_REQUEST_EEPROM
dakejahl Mar 13, 2026
d0917c7
refactor(mavlink): remove dead request_message() from ESC_EEPROM
dakejahl Mar 13, 2026
79cf083
fix(dshot): reduce serial telemetry timeout from 30ms to 5ms
dakejahl Mar 13, 2026
2d75ffe
fix(dshot): adaptively skip unresponsive serial telemetry motors
dakejahl Mar 14, 2026
8f61f14
fix(dshot): use sentinel -1 for telemetry motor index when idle
dakejahl Mar 14, 2026
dfb1a76
fix(dshot): add DSHOT_MAX_MOTORS to bound motor-indexed arrays
dakejahl Mar 14, 2026
427931e
fix(dshot): move DSHOT_MAX_MOTORS to DShotCommon.h, fix DShotTelemetr…
dakejahl Mar 14, 2026
9618403
fix(dshot): document intentionally conservative online flag logic
dakejahl Mar 14, 2026
60ffaf5
fix(dshot): match EscEepromWrite data size to EscEepromRead (48 bytes)
dakejahl Mar 14, 2026
a0201bc
fix(dshot): bootstrap serial telemetry round-robin from sentinel state
dakejahl Mar 14, 2026
e18fd8e
perf(dshot): precompute bdshot capture delay at init
dakejahl Mar 14, 2026
38722cc
perf(dshot): replace bdshot ready scan with bitmask
dakejahl Mar 14, 2026
91588d1
perf(dshot): cache motor count, use __builtin_popcount
dakejahl Mar 14, 2026
84cc85a
perf(dshot): remove unnecessary memset of dshot_capture_buffer
dakejahl Mar 14, 2026
0629555
simplify(dshot): extract motor_index_from_output() helper
dakejahl Mar 14, 2026
1022ff2
simplify(dshot): use switch for timer config mapping in initialize_ds…
dakejahl Mar 14, 2026
288b32a
simplify(dshot): express online-flag logic as single boolean in consu…
dakejahl Mar 14, 2026
fd71456
simplify(dshot): extract resetCommandResponse() and use memcpy in DSh…
dakejahl Mar 14, 2026
0f249b5
simplify(dshot): replace State enum with local bool in updateOutputs()
dakejahl Mar 14, 2026
181ab2f
format(dshot): make format
dakejahl Mar 14, 2026
0faf173
fix(dshot): add bounds check to dshot_motor_data_set()
dakejahl Mar 14, 2026
2915d96
fix(dshot): pass motor mask to initSettingsHandlers()
dakejahl Mar 14, 2026
d89e7d4
fix(dshot): reset command response state on invalid motor index
dakejahl Mar 14, 2026
e1d0d4e
fix(dshot): return parsed mask from NXP up_bdshot_get_ready_mask()
dakejahl Mar 14, 2026
af384c5
fix(dshot): match _serial_port_path definition size to declaration
dakejahl Mar 14, 2026
a1252ba
fix(msg): update esc_address comment for 12-ESC support
dakejahl Mar 14, 2026
e3defb0
fix(dshot): fix typo in comment
dakejahl Mar 14, 2026
158e74d
fix(msg): add missing unit annotation in EscEepromRead.msg
dakejahl Mar 14, 2026
bb18048
Merge branch 'main' into dev/dshot_stuff2
dakejahl Mar 16, 2026
7d767fd
docs(dshot): remove references to CLI commands
dakejahl Mar 17, 2026
b903770
Revert "perf(dshot): remove unnecessary memset of dshot_capture_buffer"
dakejahl Mar 17, 2026
9f42130
fix(commander): ignore VEHICLE_CMD_ESC_REQUEST_EEPROM
dakejahl Mar 17, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
433 changes: 433 additions & 0 deletions Tools/bdshot_analyzer.py

Large diffs are not rendered by default.

6 changes: 0 additions & 6 deletions boards/ark/fmu-v6x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 0 additions & 3 deletions boards/ark/fmu-v6x/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -410,9 +410,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
Expand Down
1 change: 1 addition & 0 deletions boards/ark/fpv/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
Comment thread
dakejahl marked this conversation as resolved.
Outdated
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
Expand Down
Binary file modified boards/ark/fpv/extras/ark_fpv_bootloader.bin
Binary file not shown.
19 changes: 19 additions & 0 deletions boards/ark/fpv/init/rc.board_airframes
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
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
2106_albatross
13200_generic_vtol_tailsitter
13030_generic_vtol_quad_tiltrotor
3 changes: 0 additions & 3 deletions boards/ark/fpv/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -297,9 +297,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
Expand Down
3 changes: 0 additions & 3 deletions boards/ark/pi6x/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -300,9 +300,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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 6 additions & 4 deletions boards/holybro/kakuteh7-wing/src/timer_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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}),
Expand Down
2 changes: 2 additions & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ set(msg_files
DistanceSensorModeChangeRequest.msg
DronecanNodeStatus.msg
Ekf2Timestamps.msg
EscEepromRead.msg
EscEepromWrite.msg
EscReport.msg
EscStatus.msg
EstimatorAidSource1d.msg
Expand Down
7 changes: 7 additions & 0 deletions msg/EscEepromRead.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
uint64 timestamp # [us] Time since system start
Copy link
Copy Markdown
Contributor

@hamishwillee hamishwillee Feb 3, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For all of these can you add a message description for all of these https://docs.px4.io/main/en/uorb/uorb_documentation#message-description

# Short description
#
# Long description.

uint8 firmware # ESC firmware type (see ESC_FIRMWARE enum in MAVLink)
uint8 index # [-] Index of the ESC (0 = ESC1, 1 = ESC2, etc.)
uint16 length # [-] Length of valid data
uint8[192] data # [-] Raw ESC EEPROM data

uint8 ORB_QUEUE_LENGTH = 8 # To support 8 queued up responses
8 changes: 8 additions & 0 deletions msg/EscEepromWrite.msg
Original file line number Diff line number Diff line change
@@ -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
47 changes: 24 additions & 23 deletions msg/EscReport.msg
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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!
48 changes: 26 additions & 22 deletions msg/EscStatus.msg
Original file line number Diff line number Diff line change
@@ -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
3 changes: 2 additions & 1 deletion msg/versioned/ActuatorMotors.msg
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@ uint64 timestamp_sample # [us] Sampling timestamp of the data this control resp

uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible

uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 #
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
uint8 ACTUATOR_FUNCTION_MOTOR12 = 112

uint8 NUM_CONTROLS = 12 #
float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors)
8 changes: 8 additions & 0 deletions msg/versioned/VehicleCommand.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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
Expand Down
43 changes: 25 additions & 18 deletions platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -497,22 +499,12 @@ void up_bdshot_erpm(void)
}


int up_bdshot_num_erpm_ready(void)
{
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;
int up_bdshot_num_errors(uint8_t channel)
{
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)) {
Expand All @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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;
Expand Down
Loading
Loading