Potentially incomplete Dshot implementation?
-
Hello,
I am trying to implement Dshot on our hexacopter, but I'm noticing 2 issues.
First, it looks like the signal has some inconsistency, as you can see in this video. This causes my Dshot ESC's signal integrity verification to fail, and as such it doesn't seem like I will be able to use Dshot with this flight controller at all as is.
Second, Dshot only appears to even attempt to run on the first 4 outputs - I'm just seeing a high signal on all other outputs.
Are there potential solutions to these issues, or are there hardware conflicts preventing Dshot from being usable for a hexacopter with this FC? We purchased this flight controller in part hoping that it would allow us to run Dshot on our hexacopter, so this issue is quite important to us.
Thank you,
Gus -
Hi @gus ,
For item 1, thanks for the video. Are you using the FW that shipped on the flight controller or have you updated anything? Can you share your PX4 configuration?
For item 2, we've only tested DShot on a quad, let me get someone looking at the the upper actuator outputs (5-8).
In the PX4 docs on DShot, it's claiming only the first four channels can be used on the standard hardware (https://docs.px4.io/v1.10/en/peripherals/dshot.html). But I'm not positive about our hardware so let us check that out.
Thanks!
Travis -
Hey Travis, thanks for the reply.
After further investigation I believe those bits that look inconsistent may actually be correct. It only looks like that when I enable Dshot telemetry, and of course bit 12 is the telemetry request bit. I'm not sure exactly how dshot works but I guess it makes sense that this bit isn't high on every message, since the telemetry maybe sort of 'cycles' through each output.
I am in fact able to get my dshot ESC to recognize the signal if I set the outputs to pwm, reboot, select dshot, and reboot again. I actually experienced the same thing when I was trying dshot on the Cube, so I think this aspect is fine on your end.
As far as outputs 5-8, it looks like they are on a different timer than outputs 1-4 (see boards\modalai\src\timer_config.cpp). The first 4 outputs run on Timer1 and the next 4 on Timer4, and they are initialized differently. Could your team investigate whether Timer4 is capable of Dshot? I get a little fuzzy on programming this low-level.
Cheers,
Gus -
Alright I couldn't help myself - so it does look like Timer4 can in fact handle DShot. I replaced the second timer initialization with
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2})
following the Timer4 structure listed in nuttx/src/px4/stm/stm32f7/include/px4_arch/hw_description.h
Doing that produced some interesting results. I can get DShot but it's mapped strangely, what I put on output 5 instead maps to output 7, and output 6 maps to output 5. Not sure exactly why that is, but despite that the Dshot message is certainly correct. I tested this using a test mixer where I directly mapped the throttle to a given output, and everything seemed right. Haven't tested whether telemetry works with this output mapping yet though.
Let me know if you guys investigate further.
Thanks
-
Hi @gus ,
Sounds like promising news, what FW are you using? The 1.10 release?
The timer init changed a bit with 1.11, and an early release of 1.10 had some issues with actuator output mapping (not what we are shipping), so I'm trying to get a hold on what release you are targeting.
Thanks!
Travis -
@modaltb This is on release 1.11.1.
-
-
Thanks for the heads up!