PX4-Autopilot
PX4-Autopilot copied to clipboard
fmuv6xrt implement bidirectional dshot
Partial continuation of #20749 but then on fmuv6xrt hardware.
So I took over the DSHOT_BIDIR_EN
and init sequences
The low level dshot driver fully support bidirectional dshot on 8 channels.
In the current pr you can read out it through dshot status
INFO [dshot] telemetry on: /dev/ttyS6
INFO [dshot] Number of successful ESC frames: 3086
INFO [dshot] Number of timeouts: 209
INFO [dshot] Number of CRC errors: 0
INFO [arch_dshot] Channel 0 online Last erpm 1112 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 2 0 5248
But also get interleaved with the esc_status
publisher allowing co-existence with dshot telemetry
nsh> listener esc_status
TOPIC: esc_status
esc_status
timestamp: 65229154 (0.000968 seconds ago)
counter: 51134
esc_count: 1
esc_connectiontype: 5
esc_online_flags: 1 (0b1)
esc_armed_flags: 1 (0b1)
esc[0] (esc_report):
timestamp: 65229154 (0.005465 seconds ago)
esc_errorcount: 0
esc_rpm: 15857
esc_voltage: 12.05000
esc_current: 0.00000
esc_temperature: 0.00000
failures: 0
esc_address: 0
esc_cmdcount: 0
esc_state: 0
actuator_function: 101
esc_power: 0
Biggest open point is how to fetch the dshot erpm and publish them over uORB
We are using PX4 and a fmuv6xrt to interface a new acoustic vector sensor on a multicopter with dshot ESCs. Thank you @PetervdPerk-NXP for coincidentally working on this PR in the same timeframe that we can use this. Our module runs as a task, so a uORB subscription callback would be an ideal interfacing mechanism.
The eRPM values will be used as a component of a spatial filter to remove as much drone egonoise as possible. Ideally, published RPM values are available at the same rate as the motor update interval, but with much of our processing in the frequency domain, buffering and reasonable latencies are fine. We will certainly end up averaging/filtering the eRPM values.
Hope this helps.
Depends on https://github.com/PX4/NuttX/pull/297
Biggest open point is how to fetch the dshot erpm and publish them over uORB. Currently the dhost driver setpoint and trigger gets called by wq:rate_ctrl but for fetching the dshot erpm do we implement callback as proposed in https://github.com/PX4/PX4-Autopilot/pull/20749 ? Or should we schedule a work-queue to fetch it, and if so which work-queue then?
Either way works for me. We can initially just store the result in the callback, then publish on the next motor update iteration to uORB.
Modified to work in conjunction to work with UART based telemetry
TOPIC: esc_status
esc_status
timestamp: 29181243 (0.000752 seconds ago)
counter: 18794
esc_count: 1
esc_connectiontype: 5
esc_online_flags: 0
esc_armed_flags: 1 (0b1)
esc[0] (esc_report):
timestamp: 29181243 (0.000752 seconds ago)
esc_errorcount: 0
esc_rpm: 32628
esc_voltage: 0.00000
esc_current: 0.00000
esc_temperature: 0.00000
failures: 0
esc_address: 0
esc_cmdcount: 0
esc_state: 0
actuator_function: 0
esc_power: 0
Needs testing @bkueng are you be able test this on a real drone or @dk7xe could you help out here?
If i get access to bidirectional Dshot ESC, yes. @ronlix would you have something for testing?
I currently don't have a setup
Yesterday I cherry-picked the three commits into my fmu6xrt build based on PX4 v14.2, and tried this feature out on a new quadcopter build with four dshot 1200 ESCs. Prior to the update, I was able to read the RPM, voltage, and current over the 3rd telemetry wire, using the ESC_STATUS uORB message, but not after, and also there is nothing being streamed out TELEM1. Before the update, I captured this info from ESC #1:
nsh> dshot esc_info -m 1
INFO [dshot] ESC Type: #TEKKO32_F4#
INFO [dshot] MCU Serial Number: d93c31-000040-74741a-b74009
INFO [dshot] Firmware version: 32.90
INFO [dshot] Rotation Direction: normal
INFO [dshot] 3D Mode: off
INFO [dshot] Low voltage Limit: off
INFO [dshot] Current Limit: off
INFO [dshot] LED 0: on
INFO [dshot] LED 1: on
INFO [dshot] LED 2: on
INFO [dshot] LED 3: unsupported
After the update, I was not able to get a response either from ESC_STATUS, or dshot esc_info. When DSHOT_BIDIR_EN is false, the system will ARM and spin the propellers, but with no telemetry. When DSHOT_BIDIR_EN is true, I get ESC 156 offline errors for all motors during ARM, even though the parameter COM_ARM_CHK_ESCS is disabled. Note that even with DSHOT_BIDIR_EN true, I am able to manually spin the propellers using Actuator Setup. They just won't ARM.
Appended below are the dmesg logs obtained with the new code, for two cases: DSHOT_BIDIR_EN true and false. We could use this feature ASAP, I'm happy to help move this along. Please suggest what debugging logs/messages/strategies would assist in this goal.
dmesg (DSHOT_BIDIR_EN false):
nsh> dmesg
HW arch: PX4_FMU_V6XRT
HW type: V6XRT
HW FMUM ID: 0x000
HW BASE ID: 0x000
PX4 git-hash: 7ec65b960484cc2bfaa21c9f8939c3cf0b53378a
PX4 version: 1.15.0 0 (17760256)
PX4 git-branch: ares_dshot
OS: NuttX
OS version: Release 11.0.0 (184549631)
OS git-hash: 693b9e782535f12e6a4ab657c7a0c3bd92b45fb1
Build datetime: Mar 12 2024 07:18:20
Build uri: localhost
Build variant: default
Toolchain: GNU GCC, 9.3.1 20200408 (release)
PX4GUID: 000900000000000000008292b37f0c33580e
MCU: i.MX RT1170 rB0, rev. 0
INFO [param] selected parameter default file /fs/mtd_params
INFO [param] importing from '/fs/mtd_params'
INFO [parameters] BSON document size 2767 bytes, decoded 2767 bytes (INT32:60, FLOAT:76)
INFO [param] selected parameter backup file /fs/microsd/parameters_backup.bson
Board architecture defaults: /etc/init.d/rc.board_arch_defaults
Board defaults: /etc/init.d/rc.board_defaults
ifup can0...OK
ifup can1...OK
ifup can2...OK
Loading airframe: /etc/init.d/airframes/4019_x500_v2
INFO [dataman] data manager file '/fs/microsd/dataman' size is 68528 bytes
INFO [px4io] IO FW CRC match
Board sensors: /etc/init.d/rc.board_sensors
ads1115 #0 on I2C bus 1 address 0x48
INFO [ina226] Failed to init INA226 on bus 1, but will try again periodically.
ina226 #0 on I2C bus 1 (external) address 0x41
INFO [ina226] Failed to init INA226 on bus 2, but will try again periodically.
ina226 #1 on I2C bus 2 (external) address 0x41
INFO [ads1115] ADS1115: reported ready
icm42686p #0 on SPI bus 1 rotation 12
ERROR [ads1115] ADS1115: not ready. Device lost?
bmi088_accel #0 on SPI bus 3 rotation 4
INFO [ads1115] ADS1115: reported ready
bmi088_gyro #0 on SPI bus 3 rotation 4
ERROR [ads1115] ADS1115: not ready. Device lost?
icm42688p #0 on SPI bus 2 rotation 6
INFO [ads1115] ADS1115: reported ready
bmm150 #0 on I2C bus 3 address 0x10
ERROR [ads1115] ADS1115: not ready. Device lost?
WARN [SPI_I2C] ist8310: no instance started (no device on bus?)
INFO [ads1115] ADS1115: reported ready
bmp388 #0 on I2C bus 3 address 0x77
ERROR [ads1115] ADS1115: not ready. Device lost?
bmp388 #1 on I2C bus 2 (external) address 0x76
INFO [ads1115] ADS1115: reported ready
ERROR [ads1115] ADS1115: not ready. Device lost?
INFO [ads1115] ADS1115: reported ready
ERROR [ads1115] ADS1115: not ready. Device lost?
INFO [ads1115] ADS1115: reported ready
WARN [vehicle_angular_velocity] no gyro selected, using sensor_gyro_fifo:0 2949130
ekf2 [526:237]
Board mavlink: /etc/init.d/rc.board_mavlink
Starting DShot Driver on /dev/ttyS2
Starting Main GPS on /dev/ttyS1
Conflicting config for /dev/ttyS2
Starting MAVLink on ethernet
INFO [mavlink] mode: Normal, data rate: 100000 B/s on udp port 14550 remote port 14550
INFO [logger] logger started (mode=all)
INFO [cyphal] Node ID 1, bitrate 4000000
INFO [cyphal] subscribed to GnssPosition, port 1236
INFO [cyphal] subscribed to GnssRelPosNed, port 1234
INFO [cyphal] subscribed to BearingAngles, port 1243
INFO [cyphal] subscribed to AdcFrame, port 1244
INFO [cyphal] subscribed to GnssPosition, port 1236
INFO [cyphal] subscribed to GnssRelPosNed, port 1234
NuttShell (NSH) NuttX-11.0.0
INFO [cyphal] subscribed to BearingAngles, port 1243
nsh> INFO [cyphal] subscribed to AdcFrame, port 1244
WARN [mavlink] no broadcasting address found
INFO [mavlink] using network interface eth0, IP: 192.168.10.75
INFO [mavlink] with netmask: 255.255.255.0
INFO [mavlink] and broadcast IP: 192.168.10.255
INFO [mavlink] partner IP: 192.168.10.73
INFO [commander] Armed by external command
INFO [logger] Start file log (type: full)
INFO [logger] [logger] /fs/microsd/log/2024-03-12/14_58_03.ulg
INFO [logger] Opened full log file: /fs/microsd/log/2024-03-12/14_58_03.ulg
INFO [commander] Pilot took over using sticks
INFO [mavlink] Starting mavlink shell
nsh>
nsh>
nsh> dshot status
INFO [dshot] Outputs initialized: yes
INFO [dshot] Outputs used: 0xf
INFO [dshot] Outputs on: yes
dshot: cycle: 55787 events, 1345039us elapsed, 24.11us avg, min 11us max 55us 7.087us rms
INFO [mixer_module] Param prefix: PWM_AUX
control latency: 55793 events, 39448328us elapsed, 707.05us avg, min 155us max 27179us 1374.068us rms
INFO [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 99, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 1: func: 102, value: 103, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 2: func: 103, value: 99, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 3: func: 104, value: 103, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
INFO [dshot] telemetry on: /dev/ttyS2
INFO [dshot] Number of successful ESC frames: 0
INFO [dshot] Number of timeouts: 2892
INFO [arch_dshot] Channel 0 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 0 0 71409
INFO [arch_dshot] Channel 1 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 0 0 71413
INFO [arch_dshot] Channel 2 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 0 0 71420
INFO [arch_dshot] Channel 3 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 0 0 71425
nsh>
nsh> dshot esc_info -m 1
ERROR [dshot] No data received. If telemetry is setup correctly, try again
nsh>
nsh> listener esc_status
TOPIC: esc_status
nsh>
dmesg (DSHOT_BIDIR_EN on, ARM not permitted):
NuttX-11.0.0
nsh>
nsh> dmesg
HW arch: PX4_FMU_V6XRT
HW type: V6XRT
HW FMUM ID: 0x000
HW BASE ID: 0x000
PX4 git-hash: 7ec65b960484cc2bfaa21c9f8939c3cf0b53378a
PX4 version: 1.15.0 0 (17760256)
PX4 git-branch: ares_dshot
OS: NuttX
OS version: Release 11.0.0 (184549631)
OS git-hash: 693b9e782535f12e6a4ab657c7a0c3bd92b45fb1
Build datetime: Mar 12 2024 07:18:20
Build uri: localhost
Build variant: default
Toolchain: GNU GCC, 9.3.1 20200408 (release)
PX4GUID: 000900000000000000008292b37f0c33580e
MCU: i.MX RT1170 rB0, rev. 0
INFO [param] selected parameter default file /fs/mtd_params
INFO [param] importing from '/fs/mtd_params'
INFO [parameters] BSON document size 2787 bytes, decoded 2787 bytes (INT32:61, FLOAT:76)
INFO [param] selected parameter backup file /fs/microsd/parameters_backup.bson
Board architecture defaults: /etc/init.d/rc.board_arch_defaults
Board defaults: /etc/init.d/rc.board_defaults
ifup can0...OK
ifup can1...OK
ifup can2...OK
Loading airframe: /etc/init.d/airframes/4019_x500_v2
INFO [dataman] data manager file '/fs/microsd/dataman' size is 68528 bytes
INFO [px4io] IO FW CRC match
Board sensors: /etc/init.d/rc.board_sensors
ads1115 #0 on I2C bus 1 address 0x48
INFO [ina226] Failed to init INA226 on bus 1, but will try again periodically.
ina226 #0 on I2C bus 1 (external) address 0x41
INFO [ina226] Failed to init INA226 on bus 2, but will try again periodically.
ina226 #1 on I2C bus 2 (external) address 0x41
INFO [ads1115] ADS1115: reported ready
icm42686p #0 on SPI bus 1 rotation 12
ERROR [ads1115] ADS1115: not ready. Device lost?
bmi088_accel #0 on SPI bus 3 rotation 4
INFO [ads1115] ADS1115: reported ready
bmi088_gyro #0 on SPI bus 3 rotation 4
ERROR [ads1115] ADS1115: not ready. Device lost?
icm42688p #0 on SPI bus 2 rotation 6
INFO [ads1115] ADS1115: reported ready
bmm150 #0 on I2C bus 3 address 0x10
ERROR [ads1115] ADS1115: not ready. Device lost?
WARN [SPI_I2C] ist8310: no instance started (no device on bus?)
INFO [ads1115] ADS1115: reported ready
bmp388 #0 on I2C bus 3 address 0x77
ERROR [ads1115] ADS1115: not ready. Device lost?
bmp388 #1 on I2C bus 2 (external) address 0x76
INFO [ads1115] ADS1115: reported ready
ERROR [ads1115] ADS1115: not ready. Device lost?
INFO [ads1115] ADS1115: reported ready
ERROR [ads1115] ADS1115: not ready. Device lost?
INFO [ads1115] ADS1115: reported ready
WARN [vehicle_angular_velocity] no gyro selected, using sensor_gyro_fifo:0 2949130
ekf2 [526:237]
Board mavlink: /etc/init.d/rc.board_mavlink
Starting DShot Driver on /dev/ttyS2
Starting Main GPS on /dev/ttyS1
Conflicting config for /dev/ttyS2
Starting MAVLink on ethernet
INFO [mavlink] mode: Normal, data rate: 100000 B/s on udp port 14550 remote port 14550
INFO [logger] logger started (mode=all)
INFO [cyphal] Node ID 1, bitrate 4000000
INFO [cyphal] subscribed to GnssPosition, port 1236
INFO [cyphal] subscribed to GnssRelPosNed, port 1234
INFO [cyphal] subscribed to BearingAngles, port 1243
INFO [cyphal] subscribed to AdcFrame, port 1244
INFO [cyphal] subscribed to GnssPosition, port 1236
INFO [cyphal] subscribed to GnssRelPosNed, port 1234
NuttShell (NSH) NuttX-11.0.0
INFO [cyphal] subscribed to BearingAngles, port 1243
nsh> INFO [cyphal] subscribed to AdcFrame, port 1244
WARN [mavlink] no broadcasting address found
WARN [health_and_arming_checks] ESC156 offline.
WARN [health_and_arming_checks] ESC156 ESC156 ESC156 ESC156 offline.
INFO [mavlink] using network interface eth0, IP: 192.168.10.75
INFO [mavlink] with netmask: 255.255.255.0
INFO [mavlink] and broadcast IP: 192.168.10.255
INFO [mavlink] partner IP: 192.168.10.73
WARN [health_and_arming_checks] ESC156 ESC156 ESC156 ESC156 offline.
WARN [health_and_arming_checks] ESC156 ESC156 ESC156 ESC156 offline.
INFO [mavlink] Starting mavlink shell
WARN [health_and_arming_checks] ESC156 ESC156 ESC156 ESC156 offline.
nsh>
nsh> dshot status
INFO [dshot] Outputs initialized: yes
INFO [dshot] Outputs used: 0xf
INFO [dshot] Outputs on: yes
dshot: cycle: 81896 events, 2420645us elapsed, 29.56us avg, min 11us max 99us 8.283us rms
INFO [mixer_module] Param prefix: PWM_AUX
control latency: 81900 events, 58000922us elapsed, 708.19us avg, min 155us max 27850us 1209.689us rms
INFO [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 1: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 2: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 3: func: 104, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
INFO [dshot] telemetry on: /dev/ttyS2
INFO [dshot] Number of successful ESC frames: 0
INFO [dshot] Number of timeouts: 3325
INFO [arch_dshot] Channel 0 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 3 0 4356
INFO [arch_dshot] Channel 1 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 37 0 4279
INFO [arch_dshot] Channel 2 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 87 0 4113
INFO [arch_dshot] Channel 3 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 189 0 4044
nsh>
Hi @jwwaite
Thanks a lot for testing, I see you're using a TEKKO32_F4. Is it the same as this one https://holybro.com/products/tekko32-f4-4in1-50a-esc
Looking at the output I see CRC errors, are you running BDSHOT on 1200? Does lowering to 600 or 300 improve it?
Overall breaking telemetry with normal DSHOT is not good, I would have to look further into that. Maybe this merging BDSHOT with TELEM goes wrong.
Hi @PetervdPerk-NXP, These are the ESCs: [https://holybro.com/products/tekko32-f4-45a-esc] (one for each motor)
I will drop the DSHOT speed and look at the results. With respect to "3rd wire" vs bi-directional telemetry, aren't both methods designed to coexist? If so, I should be able to read the third wire into TELEM1 (which also has voltage and current), while TELEM2 outputs RPM at a higher rate?
Jim
Thanks I've been testing with Aikon AK32 35A 2-6S ESC running BLHeli_32 that unfortunely doesn't have a telemetry wire. I'll see if I can get other ESC's with BDSHOT and telemetry to improve my test coverage.
With respect to "3rd wire" vs bi-directional telemetry, aren't both methods designed to coexist? If so, I should be able to read the third wire into TELEM1 (which also has voltage and current), while TELEM2 outputs RPM at a higher rate?
We should check the BLHeli_32 documentation to determine if that's possible.
Btw there are even some ESC's that can output voltage and current over BDSHOT using Extended DShot Telemetry (EDT) but haven't acquired ESC's that run the correct version of BLHeli_32 to support that either. https://brushlesswhoop.com/dshot-and-bidirectional-dshot/#extended-dshot-telemetry-edt
Dropping the DSHOT rate to 600 eliminated all the CRC errors. This quad is a fairly large 600 mm frame, and all the ESC wires are unshielded twisted pair. No problem running at the lower speed if necessary. If we can get RPM data at half that rate, we're good.
There still isn't any telemetry information presented in the dshot app, or on the serial line. In my setup, TELEM1 reads the 3rd wire telemetry info, which works correctly in the pre-PR dshot code (RPM, voltage, and current all present in the ESC_STATUS message, but at a slow rate with latency), but is missing in the PR code. I've set TELEM2 as the output port in the new code, and nothing is there either.
I've seen that blog post on DSHOT before. In fact, it seems to be the closest thing to a specification that exists online. Note, that post specifically mentions that the 3rd dedicated back-channel wire carrying telemetry information is not really part of the DSHOT protocol. Thus, I would expect that ESCs that implement the first method that also support bi-directional DSHOT could do both in parallel. But you're right, we should check. In any event, if present, the dshot driver should allow 3rd wire data to pass through.
I need to put the dshot RPM data out over Cyphal-CAN, not read it from a UART. So, I'm not sure why UART telemetry is even necessary for bi-directional dshot. Why not just leave the existing 3rd wire telemetry code in place, including the lower rate esc_status pub, and add a new dshot telemetry message and pub at a higher rate? Initially this could be just the RPM, but for ESCs that support EDT there could be additional data.
Merging of data come from a dev call discussion with @dagar.
Idea is to support all 3 telemetry methods
- Telemetry over UART/1-wire
- Telemetry over bidirectional dshot
- Telemetry over both UART/1-wire bidirectional dshot.
I hope to receive my ESC with a telemetry next week to see why this PR breaks case 1 and 3.
As far as i know bidirectional dshot was implemented because Betaflight is using RPM for control loop. To do not block the dataline that long and to stay in sync just eRPM is reported back. All other telemetry values are still reported via the normal telemetry line. This is what ESC's with bidirectional have implemented nowadays. The extension to more telemetry values over dshot is quite new and not yet implemented widely.
@jwwaite I've found the culprit and got it work with bdshot to work with UART telemetry simultaneously. If you could test it and verify it's working with your setup then it's ready for review.
esc[0]
is an TEKKO32_F4 with telemetry
esc[1]
is an AK32 without telemetry but with bdshot
Also added a CRC error counter for UART telemetry.
TOPIC: esc_status
esc_status
timestamp: 268141231 (0.000680 seconds ago)
counter: 15376
esc_count: 2
esc_connectiontype: 5
esc_online_flags: 3 (0b11)
esc_armed_flags: 1 (0b1)
esc[0] (esc_report):
timestamp: 268141231 (0.004914 seconds ago)
esc_errorcount: 0
esc_rpm: 15857
esc_voltage: 12.04000
esc_current: 0.02000
esc_temperature: 0.00000
failures: 0
esc_address: 0
esc_cmdcount: 0
esc_state: 0
actuator_function: 101
esc_power: 0
esc[1] (esc_report):
timestamp: 268141232 (0.052961 seconds ago)
esc_errorcount: 0
esc_rpm: 21942
esc_voltage: 0.00000
esc_current: 0.00000
esc_temperature: 0.00000
failures: 0
esc_address: 0
esc_cmdcount: 0
esc_state: 0
actuator_function: 102
esc_power: 0
I tried the new code (once again, cherry-picked in), but moving the system to ARM results in an ESC failure message.
Shortly thereafter, the Nuttx reboots, and this occurs cyclically about every 5 to 10 seconds. I was not able to get the motors to spin, and so wasn't ever able to record a valid RPM.
When BIDIR dshot is disabled, the reboots still persist. However, whether or not BIDIR is enabled I can use QGC Setup to manually spin the propellers, but that mode does not allow access to the ESC_STATUS message.
nsh> dshot status
INFO [dshot] Outputs initialized: yes
INFO [dshot] Outputs used: 0xf
INFO [dshot] Outputs on: yes
dshot: cycle: 20108 events, 533912us elapsed, 26.55us avg, min 12us max 83us 8.304us rms
INFO [mixer_module] Param prefix: PWM_AUX
control latency: 20112 events, 14373671us elapsed, 714.68us avg, min 156us max 27204us 1256.807us rms
INFO [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 1: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 2: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 3: func: 104, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
INFO [dshot] telemetry on: /dev/ttyS2
INFO [dshot] Number of successful ESC frames: 1920
INFO [dshot] Number of timeouts: 650
INFO [dshot] Number of CRC errors: 0
INFO [arch_dshot] Channel 0 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 34 0 15876
INFO [arch_dshot] Channel 1 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 36 0 15812
INFO [arch_dshot] Channel 2 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 27 0 15939
INFO [arch_dshot] Channel 3 Last erpm 0 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 25 0 15867
nsh>
Since there are still CRC errors, I dropped the rate to dshot 300. The reboots still occurred.
I should mention that my 14.2 PX4 branch https://github.com/AIVS-Inc/PX4-Autopilot/tree/ares_dshot_new is 41 commits behind main, although your commits (not yet pushed) merged with no problem. I tried updating to the latest main this morning but Cyphal wasn't working on my branch. That is necessary for my system. I'll look into that issue next week, after a long weekend (back Tuesday). In the meantime, if you have some suggestions on how I can provide better debug information, let me know. I have a scope here, for example.
Unfortunately I can't access the repo you're linking, I could try your build tomorrow if I can acces it.
For testing I recommend getting a Pixhawk debug adapter using the build-in usb-uart you may be able to see see why it's crashing.
Regarding the CRC errors if it's stable I think it's manageable.
https://github.com/PX4/PX4-Autopilot/blob/eb57942f02c675c487ec1cc6a4802165318de166/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c#L303
You could play with the bdshot_tcmp
variable by changing-1
to -2
or 0
this calculates the baudrate of the telemetry unfortunately dshot isn't really exact with baudrate specifications so there's a big margin here.
Overall scoping the signal and measuring bit times would also be interesting.
Back at testing DSHOT...
- The crash was my code unrelated to dshot, not enough testing before quickly patching in your updates in anticipation of my long weekend.
- I still get the "ESC failure: failsafe activated, triggering disarm" message when trying to arm in BIDIR SHOT mode. Where is this generated? The commander parameter COM_ARM_CHK_ESCS is disabled.
Scope screenshot for bidirectional dshot (not armed, props not spinning) at 5 usec/dev, DSHOT 600. Seems that the baud rate is slightly off. I adjusted the bdshot_tcmp value by a few counts without noticeable effect.
Scope screenshot for standard dshot (armed, props spinning), also at 5 usec/div, DSHOT 600.
3rd wire telemetry values are being updated in ESC_STATUS for standard DSHOT.
This might all be working but for the "failsafe activated" ESC error. Since this circumvents arming, I can't see if there is any valid telemetry output in BIDIR mode.
I'm not into failsafe either maybe @dagar could help here.
What happens if you disable 3rd wire telemetry and only run bdshot? Do you get rpm from all motors and are you able to arm then?
I got it to work by disabling another ESC related parameter: FD_ESCS_EN. Both erpm and wired telemetry are reporting (using ESC_STATUS and dshot status to confirm). There are still a quite large number of CRC errors, for all motors, regardless of the DSHOT speed. I'll look at the effect of those counter values again.
I confirm that:
bdshot_tcmp = 0x2900 | (((FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 1) & 0xFF);
represents the lowest CRC error count, with no frame errors. Twiddling the additive value from anything other than -1 results in frame errors and a higher CRC error count. I'm running at DSHOT 1200.
I can use this now. Is there anything else you would like me to test regarding this feature?
Good to hear it's working, regarding CRC I've to check I can find a better clock divider because it's not exact and BLHeli tends to tune it's clock based on input data.
I've added a commit d6cf8cf62703d517d79398ef538e61ae98baa19b that sets drive strength, could you check if you signal looks better on your oscilloscope with this? Maybe it helps with CRC errors as well.
Overall if possible could you share a PX4 log if it's working well for you?
Got your commit, the scope signal is qualitatively the same. Here's the link to the log (manual flight mode on my desk without installed props): https://review.px4.io/plot_app?log=899f08df-9925-4d6c-bdaa-a515b63061dd
Hm I see a lot of ESC XX offline errors on your side.
What's your error rate @ Dshot1200. Looking at my scope the DShot update rate is ~900Hz. After 4 minutes (240 seconds) I got like 8 CRC errors, which roughly translates to 0.0037% CRC error rate.
With respect to error rate, "dshot status" reports CRC for [dshot], and [arch_dshot]. Here are two back-back requests for status when the motors are spinning:
nsh> dshot status INFO [dshot] Outputs initialized: yes INFO [dshot] Outputs used: 0xf INFO [dshot] Outputs on: yes dshot: cycle: 153216 events, 5931931us elapsed, 38.72us avg, min 14us max 81us 45.854us rms INFO [mixer_module] Param prefix: PWM_AUX control latency: 153220 events, 109962066us elapsed, 717.67us avg, min 157us max 27213us 5887.893us rms INFO [mixer_module] Switched to rate_ctrl work queue Channel Configuration: Channel 0: func: 101, value: 980, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 1: func: 102, value: 1110, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 2: func: 103, value: 1063, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 3: func: 104, value: 1030, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 INFO [dshot] telemetry on: /dev/ttyS2 INFO [dshot] Number of successful ESC frames: 1659875 INFO [dshot] Number of timeouts: 1242 INFO [dshot] Number of CRC errors: 3234 INFO [arch_dshot] Channel 0 Last erpm 635 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 508869 0 133265 INFO [arch_dshot] Channel 1 Last erpm 2730 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 3524 0 129741 INFO [arch_dshot] Channel 2 Last erpm 2712 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 3901 0 125792 INFO [arch_dshot] Channel 3 Last erpm 2699 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 8625 0 117829
nsh> dshot status INFO [dshot] Outputs initialized: yes INFO [dshot] Outputs used: 0xf INFO [dshot] Outputs on: yes dshot: cycle: 157265 events, 6089008us elapsed, 38.72us avg, min 14us max 81us 45.287us rms INFO [mixer_module] Param prefix: PWM_AUX control latency: 157269 events, 112866555us elapsed, 717.67us avg, min 157us max 27213us 5814.936us rms INFO [mixer_module] Switched to rate_ctrl work queue Channel Configuration: Channel 0: func: 101, value: 980, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 1: func: 102, value: 1110, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 2: func: 103, value: 1061, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 3: func: 104, value: 1029, failsafe: 0, disarmed: 0, min: 1, max: 1999 Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999 INFO [dshot] telemetry on: /dev/ttyS2 INFO [dshot] Number of successful ESC frames: 1661708 INFO [dshot] Number of timeouts: 1246 INFO [dshot] Number of CRC errors: 3234 INFO [arch_dshot] Channel 0 Last erpm 633 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 509615 0 133339 INFO [arch_dshot] Channel 1 Last erpm 2724 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 3525 0 129838 INFO [arch_dshot] Channel 2 Last erpm 2711 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 3901 0 125874 INFO [arch_dshot] Channel 3 Last erpm 2699 value INFO [arch_dshot] CRC errors Frame error No response INFO [arch_dshot] 8625 0 117913 nsh>
Regarding the dshot update rate, I see a pair of packets repeat at a 400 Hz rate (500 us/div). Is the first of the pair the speed set, and the second the telemetry output?
Did some improvements in the state machine and fixed the ESC online/offline detection with bdshot. @jwwaite hopefully your "ESC X Offline"messages should be gone now.
I definitely notice an improvement, and don't see the ESC offline errors. CRC errors relative to the "successful ESC frames" seem low enough. The difference between your observations and mine might just be the length of the signal lines to the ESCs. I'm onto other tasks, for example a simple RPM filtering function that sits on the esc_status uORB message. I'm getting updates at 270 Hz, more than enough to calculate a solid mean and variance over a 20 msec interval, which is our acoustic vector sensor processing time step.
Not sure what else needs to be done before this goes live, but it is working for my application. Thank you very much for adding this feature. The fmu-v6xrt is a really nice workhorse.
Again, two back-to-back dumps of "dshot status":
nsh> dshot status
INFO [dshot] Outputs initialized: yes
INFO [dshot] Outputs used: 0xf
INFO [dshot] Outputs on: yes
dshot: cycle: 27860 events, 1143342us elapsed, 41.04us avg, min 19us max 80us 19.377us rms
INFO [mixer_module] Param prefix: PWM_AUX
control latency: 27865 events, 20016450us elapsed, 718.34us avg, min 157us max 27288us 2294.343us rms
INFO [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 956, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 1: func: 102, value: 1098, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 2: func: 103, value: 1045, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 3: func: 104, value: 1011, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
INFO [dshot] telemetry on: /dev/ttyS2
INFO [dshot] Number of successful ESC frames: 39895
INFO [dshot] Number of timeouts: 541
INFO [dshot] Number of CRC errors: 497
INFO [arch_dshot] Channel 0 online Last erpm 731 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 230 0 14187
INFO [arch_dshot] Channel 1 online Last erpm 2725 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 52 0 14193
INFO [arch_dshot] Channel 2 online Last erpm 2709 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 71 0 13966
INFO [arch_dshot] Channel 3 online Last erpm 2693 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 127 0 13804
nsh> dshot status
INFO [dshot] Outputs initialized: yes
INFO [dshot] Outputs used: 0xf
INFO [dshot] Outputs on: yes
dshot: cycle: 31253 events, 1283246us elapsed, 41.06us avg, min 19us max 80us 18.549us rms
INFO [mixer_module] Param prefix: PWM_AUX
control latency: 31257 events, 22441341us elapsed, 717.96us avg, min 157us max 27288us 2200.497us rms
INFO [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 955, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 1: func: 102, value: 1097, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 2: func: 103, value: 1045, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 3: func: 104, value: 1012, failsafe: 0, disarmed: 0, min: 1, max: 1999
Channel 4: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 5: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 6: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 7: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 8: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 9: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 10: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
Channel 11: func: 0, value: 0, failsafe: 0, disarmed: 0, min: 99, max: 1999
INFO [dshot] telemetry on: /dev/ttyS2
INFO [dshot] Number of successful ESC frames: 41306
INFO [dshot] Number of timeouts: 547
INFO [dshot] Number of CRC errors: 588
INFO [arch_dshot] Channel 0 online Last erpm 738 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 234 0 14247
INFO [arch_dshot] Channel 1 online Last erpm 2724 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 52 0 14269
INFO [arch_dshot] Channel 2 online Last erpm 2714 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 71 0 14033
INFO [arch_dshot] Channel 3 online Last erpm 2693 value
INFO [arch_dshot] CRC errors Frame error No response
INFO [arch_dshot] 129 0 13871
nsh>
@dagar @davids5 Ready for review.
FYI @AlexKlimaj @jwwaite
@julianoes do we want to bring in your STM32 dshot PR changes with this one? I am happy to test the STM32 portion.
@julianoes do we want to bring in your STM32 dshot PR changes with this one? I am happy to test the STM32 portion.
The API additions are in https://github.com/PX4/PX4-Autopilot/blob/cfbc021e5534b3a238dfd4f27caef04173464e66/src/drivers/drv_dshot.h
You would have to implement
__EXPORT extern void up_bdshot_status(void);
__EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm);
__EXPORT extern int up_bdshot_channel_status(uint8_t channel);
I would rather just merge this PR as is, before it really becomes a huge one and go phased changes for other hardware/features, i.e. even adding Extended DShot Telemetry (EDT) as well.