Bi-directional dshot support

Bdshot is the best way to drive the Dynamic notch filter. Much faster data update than serial telemetry.

I have a quadrotor currently flying a CubeOrange. I would love to use Bi-Directional DShot and Passthrough to update the four ESC’s firmware if possible in the future.

A few facts I would love to confirm:

  1. I need to use the AUX outputs instead of MAIN outputs.
  2. The CubeOrange has six AUX outputs (AUX1-6).
  3. The six AUX outputs form two groups with their own timers (AUX1-4 and AUX5-6).
  4. Each group of AUX outputs needs to be using the same protocol within the group (e.g. PWM vs Bi-Directional DShot).
  5. There is a hardware issue with the CubeOrange that prevents Passthrough specifically on AUX1.

I could configure my quad to use Bi-Directional DShot on AUX1-4, but then I am missing Passthrough on just AUX1, which is a tad annoying. This seems to be what others have successfully done already.

Or, I could configure Bi-Directional DShot on AUX1-4 and AUX5-6, map the motors to AUX2-5. I would then get Passthrough on all four ESC’s, but at the expense of AUX1 and AUX6 needing to be running Bi-Directional DShot, which might limit their use for anything else.

Is this possible, or am I missing key facts?

I believe you are correct with everything.
So - is passthrough important enough to sacrifice two spare AUX connections ?

There’s some BLHELI settings in Arducopter, like reversing motor direction with a bitmask, so passthrough is less important. You’ll probably never change ESC settings once they are correct.
I would set all the ESCs the same using passthrough, or an arduino, then use the Arducopter params without passthrough, and use the 2 spare AUX ports for something else :slight_smile:

Then using Mission Planner motor test to get the spin direction correct, adjust:
SERVO_BLH_RVMASK
Dont forget to check
SERVO_BLH_POLES

For BLHELI32 settings in the ESCs I suggest:
Low RPM Power Protect = OFF
Temperature Protection = 100
Low Voltage Protection = OFF
and set up voltage and current monitoring via your normal power brick. I find all the ESCs report different voltages so I dont rely on them - you certainly dont want an ESC cutting out if it thinks the voltage is too low, allow the flight controller to make those choices.

I also turn on Sine Modulation, but that doesn’t seem to be widely used - I’ve never had an issue with it and ESCs have worked LONG and HARD

While it’s probably not best practice, I have had multiple successes with passthrough on AUX1 with a Cube Orange, including firmware updates.

EDIT: To be clear, this experience has been with 4.1 through 4.3 series Copter bdshot firmware, two Cubes, and 3 different 4-in-1 ESCs (Hobbywing XRotor 40A and 60A along with a Lumenier 60A).

Can we get builds for the full fat 2m Pixhawk/FMUv3, it seems odd that the 1M Pixhawk/FMUv2 has them but not the 2M. I noticed 4.4 added Bidirectional BDShot to a fair few more boards so thought now would be a good time to ask. Thanks

1 Like

Perfect thanks, even more reason to get my rebuild done so I can test this.

I’m curious if there will be support for bdshot on the Kakute H7 Mini board. It’s capable of bdshot, and the full size Kakute H7 has a bdshot fw available, but none for the mini I’m using.

Also, FWIW the link to docs on the OP is no longer working.

It’s built right in - there is no separate target. I am flying one with bdshot :slight_smile:

1 Like

Awesome thanks! I assumed the OP was still correct where it says, “Bi-directional dshot (BDShot) is only supported on some boards, mostly ending in -bdshot”. That must be based on older info, or the Kakute h7 mini just happens to not be part of that “mostly” crowd.

If your config allows you to set SERVO_BLH_BDMASK then its supported. It’s also documented in the README and wiki for each board

Gotcha, yes I was able to set SERVO_BLH_BDMASK, and there is a mention of bidirectional capability in the wiki for the board. I just wasn’t sure since the full size Kakute h7 v2 does actually have a ‘bdshot’ target and a non dshot target.

Generally if I do the initial port I try and make sure it has bdshot from the get go

1 Like

Hopfully this question is not too random for thsi thread.
I also flashed my fc (matek f405-te) with AC 4.4.3 BDshot. And followed setup steps as outlined at the top of this thread.

in messages getgin this output: 12/5/2023 9:17:08 PM : RCOut: DS600:1-2 PWM:3 DS600:4 PWM:5-12
I would expect all 4 servors are DS600. Any clues? there is nothing unusual in my setup

thansks!

hah, just saw this MateksysF405-TE BDshot? - #7 by Kopervlad

investigating …

sounds like i need to avoid channel 3 - wonder how to remap around it… and w/o resoldering the 4 signal wires

You only have to change two wires:
Move the ones connected to 2 and 3 over to 6 and 7.

There is really no other solution on that board.

ardupilot/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef.dat at master · ArduPilot/ardupilot (github.com)

1 Like

Hello
I’m using a Skystars F405 Mini HD2 flight controller, but I didn’t find a suitable target in the repository
After reading the forum I tried to assemble the firmware myself
But since there is not enough knowledge, I ran into a problem
I want to implement bidirectional DSHOT, but with these settings, only three motors rotate and transmit telemetry
Please tell me where I made a mistake

SERVO_BLH_AUTO 1
SERVO_BLH_BDMASK 15
SERVO_BLH_MASK 15
SERVO_BLH_OTYPE 5

hwdef.dat
# hw definition file for processing by chibios_pins.py
# Skystars F405HD2 Mini

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1089

# crystal frequency
OSCILLATOR_HZ 8000000

define STM32_ST_USE_TIMER 5
define CH_CFG_ST_RESOLUTION 32

# reserve 16k for bootloader
FLASH_RESERVE_START_KB 48
FLASH_SIZE_KB 1024

# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12

define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 1

# I2C Buses
I2C_ORDER I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# order of UARTs
SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 UART5 USART6 

PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# USART1
PA9 USART1_TX USART1 NODMA
PA10 USART1_RX USART1 NODMA
define DEFAULT_SERIAL1_PROTOCOL 44

define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None

# USART3 (ESC Telemetry)
PB11 USART3_RX USART3 NODMA
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None

# UART4 (GPS)
PA0 UART4_TX UART4 
PA1 UART4_RX UART4
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS

# UART5
PC12 UART5_TX UART5 NODMA
PD2 UART5_RX UART5 
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None

# USART6 (ELRS)
PC6 USART6_TX USART6
PC7 USART6_RX USART6
define DEFAULT_SERIAL6_PROTOCOL 23

# timer for RC input
PA8 TIM1_CH1 TIM1 RCININT PULLDOWN LOW

# IMU SPI
PA4 BMI270_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# Flash logging
PA15 FLASH_CS CS
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3

# OSD SPI
PB12 OSD_CS CS
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2

# BARO
PC5 BARO_CS CS

# LED
PC14 LED_BLUE OUTPUT LOW GPIO(0)
PC15 LED_GREEN OUTPUT LOW GPIO(1)
define HAL_GPIO_A_LED_PIN 0
define HAL_GPIO_B_LED_PIN 1

# DMA
DMA_PRIORITY SPI1* SPI3_RX* TIM2* TIM4*

# Motor
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50) # M1
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51) BIDIR # M2
PB4 TIM3_CH1 TIM3 PWM(3) GPIO(52) BIDIR # M3
PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53) # M4

# ADC
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
PC2 RSSI_ADC_PIN ADC1 SCALE(1)

# BUZZER
PC13 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
define HAL_BUZZER_ON 1
define HAL_BUZZER_OFF 0

# SPI
SPIDEV bmi270  SPI1 DEVID1 BMI270_CS  MODE3  1*MHZ  10*MHZ
SPIDEV dataflash SPI3 DEVID3 FLASH_CS   MODE3 32*MHZ 32*MHZ
SPIDEV osd       SPI2 DEVID2 OSD_CS     MODE0 10*MHZ 10*MHZ
SPIDEV baro      SPI2 DEVID4 BARO_CS    MODE0 10*MHZ 10*MHZ

# one IMU
IMU BMI270 SPI:bmi270 ROTATION_NONE

# one baro
BARO BMP280 SPI:baro
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_BMP280_ENABLED 1

# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_ENABLED 1

# define default battery setup
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 31.7

#### COMPASS #######
# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin

Looks like you were not the 1st to do this:
Skystars F405

I think they were going to send me one of these and then just went quiet. There is a BF unified config file - https://github.com/betaflight/unified-targets/blob/master/configs/default/SKST-SKYSTARSF405.config - so you could use my script to convert it - https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py

1 Like

Thank you
Very useful script. I fixed some bugs and added a barometer
All equipment is working normally, motors are spinning

If I turn it on, the three motors work and transmit telemetry. One motor doesn’t work
SERVO_BLH_BDMASK 15
SERVO_BLH_MASK 15

I can’t figure out how to add bidirectional DSHOT to this board
One #M4 motor is on another timer


# MOTORS
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50)    BIDIR   # M1
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51)       # M2
PB4 TIM3_CH1 TIM3 PWM(3) GPIO(52)    BIDIR   # M3
PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53)    ??   # M4
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54)       # M5
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)       # M6

hwdef.dat
# hw definition file for processing by chibios_hwdef.py
# for SKYSTARSF405 hardware.
# thanks to betaflight for pin information

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1045

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 1024

# bootloader takes first sector
FLASH_RESERVE_START_KB 48

define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1

STM32_ST_USE_TIMER 5

# SPI devices

# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2

# SPI3
PB5 SPI3_MOSI SPI3
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3

# Chip select pins
PC5 BARO_CS CS
PA15 FLASH1_CS CS
PB12 OSD1_CS CS
PA4 GYRO1_CS CS

# Beeper
PC13 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80

# SERIAL ports
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# USART1
PA10 USART1_RX USART1
PA9 USART1_TX USART1
define DEFAULT_SERIAL1_PROTOCOL 23

# USART2
PA2 USART2_TX USART2
PA3 USART2_RX USART2
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None

# USART3
PB10 USART3_TX USART3
PB11 USART3_RX USART3
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None

# UART4
PA0 UART4_TX UART4
PA1 UART4_RX UART4
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS

# UART5
PC12 UART5_TX UART5 NODMA
PD2 UART5_RX UART5 NODMA
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None

# USART6
PC6 USART6_TX USART6 NODMA
PC7 USART6_RX USART6 NODMA

# I2C ports
I2C_ORDER I2C1
# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# Servos
PC9 CAMERA1 OUTPUT GPIO(70) LOW
define RELAY2_PIN_DEFAULT 70


# ADC1
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_VOLT_SCALE 11.0
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_CURR_PIN 11
define HAL_BATT_CURR_SCALE 34.5
PC2 RSSI_ADC ADC1
define BOARD_RSSI_ANA_PIN 12
define HAL_BATT_MONITOR_DEFAULT 4

# MOTORS
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50)       # M1
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51)  BIDIR     # M2
PB4 TIM3_CH1 TIM3 PWM(3) GPIO(52)  BIDIR     # M3
PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53)       # M4
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54)       # M5
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)       # M6

# LEDs

PC14 LED0 OUTPUT LOW GPIO(90)
define HAL_GPIO_A_LED_PIN 90
PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) # M7

PC15 LED1 OUTPUT LOW GPIO(91)
define HAL_GPIO_B_LED_PIN 91
define HAL_GPIO_LED_OFF 1


# SPI Device table
SPIDEV osd SPI2 DEVID1 OSD1_CS  MODE0  10*MHZ  10*MHZ
SPIDEV bmi270 SPI1 DEVID2 GYRO1_CS  MODE3  1*MHZ  10*MHZ
SPIDEV dataflash SPI3 DEVID3 FLASH1_CS   MODE3 104*MHZ 104*MHZ

# BARO setup
SPIDEV baro SPI2 DEVID4 BARO_CS MODE0 10*MHZ 10*MHZ
BARO BMP280 SPI:baro
define HAL_BARO_ALLOW_INIT_NO_BARO 1
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_BMP280_ENABLED 1

# One IMU
#IMU Invensense SPI:bmi270 ROTATION_ROLL_180_YAW_90
IMU BMI270 SPI:bmi270 ROTATION_NONE

DMA_NOSHARE TIM4_UP TIM3_UP TIM2_UP SPI1*
DMA_PRIORITY TIM4_UP TIM3_UP TIM2_UP SPI1*


define HAL_LOGGING_DATAFLASH_ENABLED 1
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
define HAL_DEFAULT_INS_FAST_SAMPLE 3
# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12

You need to add BIDIR to M4, but you will also need to check the DMA allocation to see if its possible