Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dshot telemetry #7264

Merged
merged 2 commits into from Jan 7, 2019

Conversation

Projects
None yet
8 participants
@joelucid
Copy link
Contributor

joelucid commented Dec 21, 2018

This is a first version of dshot_telemetry which reads rpm telemetry from blheli32 escs on the dshot signal line after each dshot command. As a result the FC will be fully aware of the real time rpm of all motors, which opens up many new improvements like better filtering and motor control.

The feature does not support burst DMA and is not implemented on the HAL drivers. It's guarded by USE_DSHOT_TELEMETRY which needs to be set to enable it. If the firmware does support it the cli option dshot_telemetry needs to be set on to activate it.

The feature requires a custom blheli32 firmware which isn't yet released. This firmware implements a couple of new dshot commands which are used to manage the feature. I'm currently trying to get in touch with Felix of KISS to ensure compatibility with KISS ESCs now and going forward.

Clearly this isn't yet ready for integration, but I wanted to get the ball rolling so we can ensure safe delivery into 4.0. I would appreciate any help from devs more familiar with the driver internals to double check what I've done here.

@ledvinap
Copy link
Contributor

ledvinap left a comment

Just some random notes, I have to look into this later ...

Show resolved Hide resolved src/main/drivers/pwm_output_dshot.c
Show resolved Hide resolved src/main/drivers/pwm_output_dshot.c Outdated
Show resolved Hide resolved src/main/drivers/pwm_output_dshot.c Outdated
Show resolved Hide resolved src/main/drivers/pwm_output_dshot.c Outdated
@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 21, 2018

@joelucid: This does look interesting. Good work!

A couple of remarks:

  • can you supply a document specifying the proposed DShot telemetry protocol - this makes it easier to discuss the protocol itself, which is the important part of this to get right first time around;
  • what are your plans re getting this supported by ESCs, and how far along are you in the process of discussing this with ESC firmware maintainers / getting buy in from them?
  • this will have to be made run time configurable to work with universal targets - there will probably be boards for which there is no useable configuration not using ...N timers, and as such not supporting this.
@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

@mikeller, here's the preliminary spec:

Digital_Cmd_Spec.txt

Commands 32-35 and 42-47 have been added in the context of this feature. I currently use commands 32 and 35.

I've closely worked with Steffen Skaug, the author of blheli, blheli_s and blheli32, in designing this feature. We have both tested this (Dshot 300, Dshot 600, Dshot 1200 and Proshot 1000) on four different ESCs and three flight controllers. Steffen will be ready with a release of blheli32 when we are.

I've reached out to Felix @ KISS, but have not heard back, yet. I believe once we have support from blheli32 and KISS we can consider the feature well supported in the ESC community.

Important to adoption will be the availability of killer features using dshot telemetry. I plan to make available a new gyro/dterm filter soon (it's not xmas yet 😄), which will have such significant latency and noise suppression advantages over our current filters that it might be considered such a killer feature.

An interesting question is Blheli_s. While the current blheli32 implementation uses DMA it's conceivable that this could be implemented using interrupts on those ESCs. Steffen has no current plans of addressing the Blheli_s installed base though. But given the open source nature of Blheli_s anybody can try to add this.

The feature is run time configurable: set dshot_telemetry=on/off enables or disables it. Good point regarding the N channel motor signals. N channels cannot be used as input for timer capture and are thus not supported. I was able to fix this for the NOX board by simply using a different timer on the same pin, but clearly there may be boards where this will not work.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 22, 2018

Thanks @joelucid.

A couple of points regarding the specification:

  • I think this will need to be brought into a more detailed form - the current form leaves much open to assumptions;
  • am I right to assume that 42 to 47 are 'request telemetry value' commands? Not sure if we want to use this, or use the telemetry bit that is already baked into the protocol - sending out commands in place of motor updates isn't very elegant, which is why the telemetry bit was added in the first place;
  • not sure if there is value in super low latency telemetry for temperature, voltage, current, consumption, these should be dropped from this protocol, even more so to avoid having these changes use up most of the remaining Dshot command space;
  • not sure if there is value in adding facilities for 'ERPM' and 'ERPM period' telemetry - these seem to be redundant, and using up command space for both seems to be unnecessary;
  • after these things have been addressed, I can't see any problem with Betaflight adopting these extensions.

What does @ronlix think of this suggestion?

I guess the solution for configurations with N timers on motor pins will be to force dshot_telemetry off during config validation.

Only discovered this now, but how much effort is required to make this work with burst DMA? I think this will be a crucial part of getting this into Betaflight. Burst DMA has become a vital part of most newer flight controller designs, in terms of allowing designs that do not have DMA conflicts, and will become even more important when we look into using DMA to read gyro values.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 22, 2018

Hi,

Wouldnt it be simpler to rise the telemetry Baud to 1 or 2 MHz and add a dshot rpm request command?
You would need 4 loops to get all rpms, but you can send more then one dshot Signal each Loop if its not too fast. And on 32k there will be mostly no noticable Change in the rpms between 4 loops.

Or use dshot commands to give the escs ids to have Them answer delayed (based on the ids) so you can get all rpms with one request.

I think making the Signal Line bidirectional will make it much less robust.

Regards

Felix

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 22, 2018

@ronlix:

Wouldnt it be simpler to rise the telemetry Baud to 1 or 2 MHz and add a dshot rpm request command?
You would need 4 loops to get all rpms, but you can send more then one dshot Signal each Loop if its not too fast. And on 32k there will be mostly no noticable Change in the rpms between 4 loops.

That's a valid point. You could probably even do this based on the 'telemetry request' bit in the Dshot frame, and define a 'fast RPM telemetry' mode where the ESC sent a short RPM only telemetry frame for every request, and a full telemetry frame at a fixed time interval.

This would also get us around the current limitations on N channel motor timers and burst DMA - going back to the nightmarish situation we had with DMA conflicts before the advent of burst DMA isn't an option in my opinion.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

@mikeller,

yes 42-47 are request telemetry value commands. Given the bandwidth constraints of the dshot line we can't use the telemetry bit with the same semantics as the traditional esc telemetry because we can't send more than one value back. Certainly not everything as is done in response to the telemetry bit. Secondly the telemetry bit is already used for requesting traditional esc telemetry.

We considered adding additional bits to the dshot frame to request motor signal line telemetry. However erpm is likely the only item one wants to retrieve in real time and adding overhead to each frame for telemetry requests that happen only rarely did not seem like a good trade-off.

These dshot telemetry request commands give the FC flexibility not only in how often a given telemetry type is retrieved, but also when. For example one may issue them when the current dshot motor value has not changed much.

The only one implemented in BF for now with this PR is erpm telemetry which I consider by far the most significant for us. That said I do think the other telemetry items can be useful to avoid the extra wiring of serial telemetry. We could flag these extra commands as experimental.

The thought behind ERPM period telemetry was to enable low powered ESCs to report a value that can be converted on the FC to ERPM. This could be essential in enabling blheli_s to support this feature. On the other hand we didn't want to force 4 divisions on the FC with blheli32 escs to support low powered FCs (like SilverWare).

Burst dma should be doable once the response timing is strictly defined. That's needed since captured values are collected at update of the timer which may occur before the esc has started responding.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 22, 2018

The Basic Idea on the extra telemetry line was to Not need a bidirectional Line on throttle Line.

To have fresh rpm telemety Data Something Like mikeller Said would work fine..
Change the telemetry Type once with a dshot command to get for Example 1mhz Baud and let the escs send rpms only on a dshot tlm Bit. And then maybe every 20 requests a full tlm frame.

This would Work with all FCS and would make no extra dma Stress on both sides

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

@ronlix:

Wouldnt it be simpler to rise the tekemetry Baud to 1 or 2 MHz and add a dshot rpm request command?
You would need 4 loops to get all rpms, but you can send more then one dshot Signal each Loop if its not too fast. And on 32k there will be mostly no noticable Change in the rpms between 4 loops.

Yeah, that'd be another way to do it if the serial esc telemetry line is wired and can support that speed. Might cause compatibility problems due to filtering assuming the old baud rate though.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 22, 2018

I tested 1mhz for some time. Workes flawless :)

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

I tested 1mhz for some time. Workes flawless :)

I tested bidirectional dshot - also flawless ;)

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

But seriously: what's your concern about a bidirectional throttle line? It makes it so simple: already wired on all escs, no extra pins required on the FC which might not be there on 20mm boards etc.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 22, 2018

@joelucid:

The only one implemented in BF for now with this PR is erpm telemetry which I consider by far the most significant for us.

Agreed there - considering all of the other telemetry data isn't really useful for flight performance enhancements, does not need super low latency, and is widely supported with 'back channel telemetry', I would even go as far as to say that real time ERPM feedback is the only thing we actually need in this way.

This simplification will also make it possible to remove the need for the telemetry request commands (42 - 47), and have the ESC send a telemetry frame back after every received frame - there is no downside to this, and the data point will always be ERPM.

That said I do think the other telemetry items can be useful to avoid the extra wiring of serial telemetry. We could flag these extra commands as experimental.

Assigning most of the remaining Dshot command space on 'experimental' features sounds like a bad idea - this will probably make it impossible to add non-experimental features in the future because there are no more Dshot commands available.

The thought behind ERPM period telemetry was to enable low powered ESCs to report a value that can be converted on the FC to ERPM. This could be essential in enabling blheli_s to support this feature. On the other hand we didn't want to force 4 divisions on the FC with blheli32 escs to support low powered FCs (like SilverWare).

Ok. I see this point. But I think there is a logical mistake in there - being able to choose which one of ERPM / ERPM period to use does not enable the flight controller to determine which one will be supported by the ESCs it is communicating with, and once it knows what the ESC sends it can use that without having to configure it on the ESC. I think one of the following approaches would be better:

  • use the MSB in the ERPM frame to encode if the value is ERPM or ERPM period. The frame size seems to be big enough to support this, and for an ESC capable of calculating ERPM, doing so all of the time isn't an issue;
  • if this isn't an option, have the ESC send an 'info frame' containing this information instead of the ERPM value when disarmed - sending ERPM when disarmed doesn't make much sense anyway.
@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

Agreed there - considering all of the other telemetry data isn't really useful for flight performance enhancements, does not need super low latency, and is widely supported with 'back channel telemetry', I would even go as far as to say that real time ERPM feedback is the only thing we actually need in this way.

I'm cautious anticipating what will be needed in the future, but this is what we need to start, yes.

Assigning most of the remaining Dshot command space on 'experimental' features sounds like a bad idea - this will probably lead make it impossible to add non-experimental features in the future because there are no more Dshot commands available.

I'm pretty excited about using the motor signal line bidirectionally in general. Just makes the wiring so easy and doesn't require another uart on the FC. Can also potentially support older escs that don't yet have the backchannel. But I understand the concern of dshot command space pollution. We can certainly start with erpm only and figure out more scalable approaches to bidirectional comms if/as we actually start developing additional telemetry needs.

Ok. I see this point. But I think there is a logical mistake in there - being able to choose which one of ERPM / ERPM period to use does not enable the flight controller to determine which one will be supported by the ESCs it is communicating with, and once it knows what the ESC sends it can use that without having to configure it on the ESC.

Good point. We envisioned this to be configured on the FC but auto-config would be nicer. I'd hate to lose one of the 12 bits though (crc also used on telemetry). Info frame when disarmed would be a useful approach, I agree.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 22, 2018

But seriously: what's your concern about a bidirectional throttle line? It makes it so simple: already wired on all escs, no extra pins required on the FC which might not be there on 20mm boards etc.

with unidirection you can add simple signal amplifier and or different filters. also you dont have to swich between transmitter and receiver settings (GPIO, Timer and DMA)

im not sure what steffen is feeling here, but on ESC's you have time critical events that you need to take care of as soon as possible.. the sooner the better (the more efficient and smooth it can run the motor) adding time critical events makes this worse..

one thought, it is not much more work to emulate serial logic with the timers and DMA's, then doing Dshot. if its needed to go to a bidirectional communication, i think this would be a good way as it will "only" add more work for the FC's which have the bigger MCUs anyway ;)
on the ESC side it would then be possible to use a HW serial which will speed up things here..
also the serials have HW oversampling and HW half duplex which shoud do well.

i dont know how good the results of your new gyro filter that includes RPMs are, and if it would be worth the work ;) but maybe it is...

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 22, 2018

@joelucid:

I'm cautious anticipating what will be needed in the future, but this is what we need to start, yes.

Agreed there - we might find that there are other data points on the ESC that can be used to improve the flight performance when sent back to the flight controller with low latency - but we don't know yet what they are, but most likely they are not the current high latency telemetry data points.
For now we can get away with adding this in a 'stupid simple' way by just adding support for continuosly sending / receiving ERPM, without allocating any new Dshot commands, or by allocating 'continuos ERPM on' / 'low latency telemetry off' if we want to be forward looking, and I think this is what we should be doing for now.

I'm pretty excited about using the motor signal line bidirectionally in general. > Just makes the wiring so easy and doesn't require another uart on the FC. Can also potentially support older escs that don't yet have the backchannel. But I understand the concern of dshot command space pollution. We can certainly start with erpm only and figure out more scalable approaches to bidirectional comms if/as we actually start developing additional telemetry needs.

I don't quite follow there - 2 wire per ESC vs. 3, or 5 wires for a 4-in-one vs. 6. Does not seem a huge improvement in the big picture. As for ESCs without a telemetry pad, 'dedicated line' telemetry was always seen as something of an 'extra feature' that is nice to have, but does not provide much value beyond that, so users who don't want this will buy ESCs / flight controllers without telemetry pads. Low latency ERPM is different there, as this has the promise to add significant value in terms of flight performance, beyond just 'getting the data', so 'not interested in it' isn't really a thing.
But beyond that, my concern with adding support for full telemetry on the motor pin is more that it tries to add something to Dshot that the protocol wasn't designed for, and incurs a significant penalty in terms of complexity.
If we really want to go this way, we should have another go at it and try to come up with an improved design that doesn't try to coerce Dshot commands into something they were not designed for.
(Just as a quick idea, how about extending the length of the Dshot telemetry frame to include a 'telemetry value id' (or split every value into 2 frames), and then have the ESC stream back the values at appropriate intervals?)

Good point. We envisioned this to be configured on the FC but auto-config would be nicer. I'd hate to lose one of the 12 bits though (crc also used on telemetry). Info frame when disarmed would be a useful approach, I agree.

Yeah, on second thought 'can calculate ERPM' is a constant for any given ESC, so having the flight controller detect this once on startup is the right thing to do. Making it configurable on the ESC doesn't make sense - if the ESC is fast enough to calculate it it should - any computation that can be farmed out from the flight controller will free up CPU time for other things.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

i dont know how good the results of your new gyro filter that includes RPMs are, and if it would be worth the work ;) but maybe it is...

Well decide for yourself - this is an image of gyro, roll pids and motor traces using very narrow (q=5) notch filters on the first three motor harmonics, no other filtering on gyro and a 150hz lpf on the dterm. Total software latency of the dterm might be 2.7ms, on gyro maybe 0.5ms. Yet the traces are completely clean.

rpm_filter

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

@mikeller:

For now we can get away with adding this in a 'stupid simple' way by just adding support for continuosly sending / receiving ERPM, without allocating any new Dshot commands, or by allocating 'continuos ERPM on' / 'low latency telemetry off' if we want to be forward looking, and I think this is what we should be doing for now.

I do think we should have the two commands that we use now so that the esc only sends when it has been asked to. So "continuous rpm telemetry on" and "continuous rpm telemetry off".

I don't want to go much further discussing telemetry for other items over dshot. Live telemetry for flight control relevant esc data has the potential to revolutionize quads - see image above. That's why I wanted it. Let's push the frontiers of flight control, not get slowed down by providing convenience telemetry features.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 22, 2018

Well, the throttle signals have a Higher priority then any Feedback.
Thats why i think its saver to keep Them seperated.

But If you go that way now, please define what Bits in which Order should be sent. So i can add it to the kiss ESC Code.

If we find better ways later Things can be changed :)

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

But If you go that way now, please define what Bits in which Order should be sent. So i can add it to the kiss ESC Code.
If we find better ways later Things can be changed :)

Thanks Felix!

I think we'll be using commands 32 and 34 from this spec, to switch online rpm reporting on and off. Looks like we've tabled any additional telemetry for now since it's already provided on the serial telemetry line and in order to keep this simple.
Digital_Cmd_Spec.txt

Responses are sent as normal dshot frame included CRC. The lsb scale for the values is in the spec.

I fully agree - we can change this if we find problems. What I find most exciting for now is to get a sense for what we can do with rpm telemetry on the FC. I'm already using it for more effective filtering (#7271). But there are a lot of other ideas, like running pids for motor rpm on the FC to improve motor response.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 22, 2018

@joelucid:

I do think we should have the two commands that we use now so that the esc only sends when it has been asked to. So "continuous rpm telemetry on" and "continuous rpm telemetry off".

I fully agree - we can change this if we find problems.

I disagree there - one core part of this change is an amendment of the Dshot protocol. As it is, this has deep implications on users of the protocol, and maintainers of software implementing it - if this is changed after being published, it will leave users of the pre-change version in a lurch to find firmware for their hardware that supports the change, and maintainers of firmware in a struggle to maintain support for legacy and new versions. For these reasons, the protocol design should get utmost care to be done right the first time round.

So, I think what we should do now is to reduce the proposed protocol changes to what is actually needed, and leave options open for future extensions, which will come at a time when we have learned more on how this works out in practice:

32 DIGITAL_CMD_SIGNAL_LINE_TELEMETRY_DISABLE                  // Need 6x, no wait required. Needs to be followed by a 12 DIGITAL_CMD_SAVE_SETTINGS to persist / come into effect.
33 DIGITAL_CMD_SIGNAL_LINE_CONTINUOUS_ERPM_TELEMETRY          // Need 6x, no wait required. Needs to be followed by a 12 DIGITAL_CMD_SAVE_SETTINGS to persist / come into effect.

@sskaug, @ronlix: What are your thoughts on this.

(Addition of making this a permanent change instead of a temporary one is based on the fact that the use case for this does not contain any cases of temporary change, plus the fact that this will save the bacon in case individual ESCs reset due to brown out or other problems.)

While we are talking Dshot protocol, what are your thoughts on scraping

30 Audio_Stream mode on/Off		      // Currently not implemented
31 Silent Mode on/Off			      // Currently not implemented

These don't seem to be used, and using a single Dshot command for on/off isn't feasible, as there is no payload to encode on/off.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

@mikeller you misread my message. I said exactly what you repeated now. My openness to change was in regard to using the signal lines for telemetry. If that does cause the issues Felix worries about we can make changes. I said we want just the two commands.

I wonder though - are we talking about the same protocol? Which has four commands to switch on LED’s? The command crowding angst seems to be a new phenomenon.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 22, 2018

@joelucid: Ok, I did misread then - you were not very specific about what would be changed later. ;-)
So we are agreed on using commands 30 and 31, and 12 to save the configuration change?

The LED control commands were unilaterally added by BLHeli_32, and then accepted by Betaflight, which probably was not a good move in hindsight. But they go a long way towards showing that the command space in Dshot is very limited, and does not allow for powerful commands with parameters, and as such has to be used wisely.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 22, 2018

@mikeller I don’t think its a good idea to make this setting persistent since it would mean that after a FC change or reconfiguration the ESCs might end up sending telemetry against a line actively driven by the FC.

As I said two commands: one to switch rpm telemetry on, one to switch it off for the existing session.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 23, 2018

@joelucid:

I don’t think its a good idea to make this setting persistent since it would mean that after a FC change or reconfiguration the ESCs might end up sending telemetry against a line actively driven by the FC.

Valid point, accepted.

This will then probably require adding of detection / graceful handling of situations where some or all of the ESCs stop sending ERPM telemetry back in mid-flight.

Then how about this:

32 DIGITAL_CMD_SIGNAL_LINE_TELEMETRY_DISABLE                  // Need 6x, no wait required.
33 DIGITAL_CMD_SIGNAL_LINE_CONTINUOUS_ERPM_TELEMETRY          // Need 6x, no wait required.
@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 23, 2018

@mikeller yeah that’s how these commands were designed from the beginning and that’s how I still think they make the most sense.

Hopefully we can move on to the more meaty discussions of what to do with rpm telemetry soon.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 23, 2018

@joelucid: Happy to do so - from the perspective of having to maintain the code going forward, protocols, and their implications for backwards compatibility, are the 'meaty' part that will make our lives easy or hard in years to come.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 23, 2018

@mikeller, my professional experience is to allow flexibility in apis and protocols in beta but nail them down once released. In the early phases it’s often more important to explore the core issues than fixing the protocols. But YMMV.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 23, 2018

@joelucid: Fair enough. I assumed that this was targeting inclusion in the upcoming 4.0 release. Considering the expected turnaround time for getting protocol changes released to beta testers by BLHeli_32 and KISS (and potentially BLHeli_S), if you feel that we need a longer beta period then we should schedule this for inclusion in 4.1.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 25, 2018

Yeah I would only do downsampling if tte current rate at which the esc sends telemetry packets is lower than the commutation rate. So that we don’t introduce delay beyond what’s inherent in the telemetry rate.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 25, 2018

But If you filter the values anyway as they are too noisy, it would be be better to do it on the esc. I think of a moving avg of 4 or 5 samples. If the esc does that, it will be automaticaly adjusted to the rpm/commutation steps. If the fc does it, the commutation frequency vs Loop/request frequency will add errors to the filters.

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Dec 25, 2018

Well, to look at it "realistic". If we do a moving avg of 6 zero crossings we would get completly fresh and less noisy data each 51.4deg of one real revolution(If Motor has 14 magnetpoles as 90% of our motors) do you really think its necessary to get rpm Data more often?

This would also mean the max. Needed/sensfull tlm rate would be something like 4 khz

This is also one of the reasons why i still think that sending datas to the escs with 32k is a waste of resources ;)

@sskaug

This comment has been minimized.

Copy link

sskaug commented Dec 25, 2018

In the current BLHeli_32 implementation, the time for one erpm (6 commutations) is what is measured, so that is pretty much in line with what you outline.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 25, 2018

I don’t think 6 point averaging at max throttle matters much at all and I also agree that 32k does not offer significant advantages. But at lower rpm it does matter. Say the props idle at 50hz = 350 ehz. That’s almost 3ms of averaging period where the acceleration could be at its maximum.

And even that data as I get it from blheli32 still needs to be filtered again due to a lot of noise (iirc more than +- 15% of max amplitude).

I suspect for closed loop where we need derivatives with their noise amplification it’ll be a significant challenge. It’s actually even worse: yaw is mediated by rpm’ due to rotational momentum transfer. So to control yaw you want closed loop rpm derivative control which needs the second derivative in the d term. I ran some simulations on the blheli32 data and I think it’s basically unusable currently for that purpose. But we’ll go after these problems as they become real, not just anticipated issues.

I always like to have all data available so that I can make my own attempts at making the most of it for a given context. Just look at gyro. We used to run the hw gyro lpfs on it. Look at how much further we are now with rpm based notch filtering. Or on a taranis you can make much better 2nd stick derivative estimates looking at the high frequency raw data and applying higher order exponential smoothing that getting rc frames on the Fc.

Long story short for notch filtering I think 6 point averaging on the esc is fine. But we’ll likely have to revisit that later on.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 26, 2018

@jflyper:

Another look at the dma 2 situation on stm32f05:

ADC needs one of streams:
0 2 3 4
SPI1 RX needs one of streams:
0 2
SPI1 TX needs one of streams:
3 5
STDIO needs on of streams:
3 6
DSHOT needs two (rarely 3) of streams
1 2 3 4 5 6 7

So:
1.) Streams 1 and 7 are always available for dshot.
2.) Other than dshot 4 streams are needed.
3.) The only stream that's not usable with timer 8 or 1 (stream 0) can be used for ADC or SPI1 RX.

So far no problem. Which leaves LED. LED needs its own timer and uses the channel irq. Some configurations use timer 1 or timer 8, one of channels 1-3. We need one these timers for dshot.

The triple channel stream 2 for timer 8 or 6 for timer 1 allow us to handle any of these LED allocations. Now of the other streams:

1.) Timer 1 for dshot can use streams 1 3 4 5 6
2.) Timer 8 for dshot can use streams 1 2 3 4 7

If we need to use timer 8 we can use streams 1 and 7 are are done. If we need to use timer 1 we can use stream 1 and 3 since the allocations for ADC, SPI1 and STDIO can be met without stream 3.

So looking pretty good. In fact I think we'd likely find 3 streams to support configs with motors on 3 ports.

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 27, 2018

@mikeller, I think your requested changes are now addressed.

We need to decide how to move forward. For me using the signal lines for rpm telemetry makes the next generation features based on it accessible to a much larger audience, since the esc backchannel doesn't need to get wired. Also this could probably be made to work with BLHeli_S, again drastically widening the installed base which can take advantage of the coming features.

The current non-burst implementation can likely be made to work with a significant portion of F3 and F4 flight controllers. But there will be cases where it doesn't work due to dma conflicts or where the N channel workarounds break some features like LED. It would be great if we could change the timer selection for N channels based on whether the feature is enabled.

The gpio DMA approach outlined above will likely work on all F4 boards and might also make some DMA1 streams which are currently used by timer update DMA available for other functions. It would fit nicely with the DMA rework planned for BF.

Running low latency rpm telemetry on a quicker serial back channel would also likely address many of our needs, but only on a smaller hw set. If there are specific ESCs or FCs which have the problem Felix pointed out due to drivers etc in the signal line this would be a good way to enable them for rpm based features as well. Will probably work for all but the most bandwidth demanding applications.

I would prefer to do a first integration with the existing non burst implementation, disabled by default, to let us collect more feedback on the feature. This allows more people to start implementing features on it, too.

Maybe some BF developers who are more familiar with drivers, dma, timer internals than me could help pushing the gpio DMA approach forward. If nobody wants to, I guess I'd do that, too, but I think I'm probably more productive designing flight features on top of rpm telemetry.

@mikeller

This comment has been minimized.

Copy link
Member

mikeller commented Dec 27, 2018

@joelucid: Sorry, I've been swamped a bit with (big) reviews over the last few days. I'll catch up and come back to yours in the coming days.

As I said from the start, I can see the use case for the bidirectional backchannel for ERPM telemetry that you are proposing - transferring a stream of atomic values back to the flight controller seems to be a good match for the data format that we are using.

I am less convinced that trying to funnel the rest of the ESC telemetry through the same channel will be a good solution - but for what I understand all that you need to take it from here is ERPM, and that's what we should be doing for now, and collect more insights into how this is working along the way, helping us to better judge the potential to extend this channel in the future.

I think there are still open issues like the one of N channels and burst DMA, which will force this to be only a 'niche case' and not work out of the box for most setups to start with. The problem there is that non-burst DMA is not well supported, new flight controller designs often have not been designed / checked to be free of DMA conflicts if burst DMA isn't used, and N channel timers are often used because they are the only option for that particular pin.

We've looked into 'automatic' resolution of these conflicts, and selection of alternative timers, but the whole problem is of a complexity, and the list of constraints is so large, that this probably won't be feasible - it will be up to the user to figure out how to allocate resources to make it work. Best will probably be to start a wiki page like we did when Dshot was first implemented (without burst), and let users contribute the setups they found to be working for their use cases: https://github.com/betaflight/betaflight/wiki/DSHOT-ESC-Protocol#fc-targets-that-work-with-dshot-but-require-hardware-mods-and-re-mapping-pins-with-the-resource-command

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Dec 28, 2018

@mikeller, yes, erpm telemetry is all I need for starters and all that's implemented at the moment.

I agree about the N channel and burst DMA issues with the current implementation. Yet it does give us a valuable starting point. Which could allow us to pursue improvements on the driver and application level around bidirectional dshot in parallel.

In my view the approach I outlined earlier in this thread of using timer1 or timer8 to drive dma transfers directly to/from the gpio registers clearly has the potential to solve both. Even if it's more limited than envisioned due to the restrictions @jflyper educated me on. Namely that only DMA2 can access the gpio peripheral.

Yesterday I realized that the gpio DMA approach was also used in a paper @jflyper had initially pointed me to. I'll include it here for reference:
f4asyncdma.pdf

I think there's also an opportunity to think about our driver structure more generally. For example some of our uses of DMA don't seem to be very essential. E.g. current/voltage sensing via ADC. We sample the voltage readings at 50hz - I doubt this strictly requires a DMA. If our drivers provided DMA and irq driven modes of operation we could provide working fall backs if some DMA streams are needed for other purposes.

DMA is really essential for high throughput, timing relevant functions like flash, dshot, soft serial etc. Where there is less throughput or more high level hw support on the cpu irq driven transfers might be fine - that might even be true for gyro SPI communication and RX-spi.

A key benefit of the gpio DMA approach is that it requires way less luck with timers and pins. We just need 1-3 streams of, and exclusive access to, either timer1 or timer8. Then we can use any gpio piñ on the board as bidirectional dshot line and drive 16 - 48 motors 😄.

@mikeller
Copy link
Member

mikeller left a comment

This is looking good now. Just some minor cosmetic remarks.

Show resolved Hide resolved src/main/drivers/pwm_output.h
Show resolved Hide resolved src/main/drivers/pwm_output_dshot.c Outdated

@mikeller mikeller added this to the 4.0 milestone Dec 29, 2018

@joelucid joelucid force-pushed the joelucid:dshot_telemetry branch from 14d2f15 to 816da6c Jan 3, 2019

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Jan 3, 2019

@mikeller, Rebased and sqashed

@joelucid

This comment has been minimized.

Copy link
Contributor Author

joelucid commented Jan 5, 2019

A test version of blheli32 is now available: https://www.rcgroups.com/forums/showpost.php?p=40842949&postcount=3112

Show resolved Hide resolved src/main/target/common_pre.h Outdated

@mikeller mikeller merged commit 00e0248 into betaflight:master Jan 7, 2019

@jflyper

This comment has been minimized.

Copy link
Contributor

jflyper commented Jan 21, 2019

@ronlix @sskaug Cc: @joelucid

@jflyper as soon as i find time, i will have a look how fast the rpm can be sent over the tlm wire. I think bauds like 1 or 2m should work eaven on base clock frequencys that dont fit well, as the uarts are quite tolerant with oversampling and such.

I'm still looking at RPM telemetry over serial telemetry link. @ronlix Did you evaluate the max speed of the tlm wire?

@ronlix

This comment has been minimized.

Copy link
Contributor

ronlix commented Jan 21, 2019

Hi,

in my tests im at 2mhz ATM. it seems to work relaiable eaven with only the internal pullups (4x ESC 1xFC)
im just abaut to test some methods, including a onewire protocol where the FC requests RPM over the TLM wire as this would work independent of the used throttle signal type.

will let you know if i got something good :) and if you have ideas, im open.

@TonyBazz

This comment has been minimized.

Copy link
Contributor

TonyBazz commented Jan 23, 2019

Can i chime in??

Looking at your code, the only validation you do on the incoming frames is the CRC. The CRC is only 4 bits, which means erroneous data will still get through.

I think you should also be validating incoming frames using the frame length. You know what the expected frame, bit or nibble lengths are going to be.. so reject anything that falls outside the above thresholds.

Otherwise, If we extend Proshot we can utilise another nibble (or two) of data and generate a 8 or 12bit CRC.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
You can’t perform that action at this time.