Bit new to modifying Ardupilot. I’m wondering how to add bidirectional DShot to a board that doesn’t support it by default. In my case it’s a Mamba F405 Mk2, for which a non-BDshot target already exists. The goal of this is to get the RPM-based harmonic filter working on this pretty common and low-cost FPV-oriented board.
Looking at the hwdefs of other boards that do have BDshot (e.g. the Matek F405) I notice this is the only difference between the BDShot and non-BDshot versions:
# Bi-directional dshot version of MatekF405
include ../MatekF405/hwdef.dat
undef PC6 PC9 PA8
PC6 TIM8_CH1 TIM8 PWM(1) GPIO(50) BIDIR
PC9 TIM8_CH4 TIM8 PWM(4) GPIO(53) BIDIR
# Can only do bdshot on M1-4, so give up DMA channel on M6 to get full DMA on USART3
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(55) NODMA
DMA_NOSHARE TIM8*
From what I can understand the difference is just unallocating the 4 motor output pins, and then adding BIDIR to the new assignment. Am I right to assume that as long as the board has enough DMA channels left doing this should be enough? Or will there be more substantial code changes involved? I’d love to see some example pull requests etc. if that is the case.
Any pointers in the right direction would be greatly appreciated.
Worked like a charm, I can spin up the motors and see esc*_rpm change accordingly. Thanks for the help, will hopefully flight test and report back on results.
@andyp1per well, it worked with some caveats. With the hwdef.dat I posted it complains about this in hwdat.h: Note: The following peripherals can't be resolved for DMA: ['USART3_RX'].
If I put the line DMA_PRIORITY USART3_RX USART6_RX the comment in hwdat.h goes away, but when I flash the autopilot with the built .apj, I get a prearm error in Mission planner: internal error 0x8000 i:182 stack_ovrfl
I do have a Matek M8Q-CAN GPS/Baro connected to UART3 and communicating in MSP, this previous thread seem to suggest it’s a DMA issue, any thoughts?
It could well be a stack issue, I think i:182 is the thread priority which should be the main thread. So you might be able to play with the main thread stack size to avoid this. You can follow the instructions in that thread as to how to see the current stack sizes of all the threads. Might be CAN related - try disabling CAN and see if it goes away.
Had a few goes but no luck - looks like I’m missing some prerequisite understanding of timers and channels in order to get this right. Been digging through old threads and there’s some nice info here, and I’ll have another shot at it after I digest the information. In the meantime I’m moving to a board with native bdshot support to continue my build. Thanks for the support so far.