Maximum rate of rpm, current and voltage measurements of VOXL ESCs
-
Hi,
I would like to access RPM measurements (+current and voltage if possible) of the ESCs at the highest possible rate (2kHz is good, more is better). So what is the highest rate possible with M0129 and M0134? This is for direct connection between the ESC and a Linux PC.Another relevant question: what would be the highest rates of these measurements through PX4->Mavlink->offboard?
Thank you very much,
-
If you need the maximum throughput of the ESC feedback data, you should use the uart-to-serial connection to a linux PC, which you have already done. Additionally, the
voxl-esc
test scripts already provide an option to specify the command rate (--cmd-rate
). Please see the checklist below for best performance:- make sure the ESC baud rate is set to 2Mbit (first make sure your usb-to-serial adapter can support it). here is an example esc param file showing the baud rate set to 2Mbit. It may already be set to 2Mbit for your esc, you can verify using
voxl-esc-scan.py
- some USB to serial adapters may add some delay, sometimes it helps to experiment with a few. Any particular adapter you have in mind for testing?
- maximum command rate that has been tested is 4000hz, but it has not been tested extensively, i suggest starting with 2000hz.
- keep in mind that in order to achieve the maximum rate of esc feedback, you should only test / request feedback from one ESC at a time. The
voxl-esc-spin.py
test script will request feedback from a single ESC if you only spin one motor (using--id 0
, for example), and will automatically request feedback from all ESC at 1/4 of the rate if you spin all motors (using--id 255
). So if yourcmd-rate
is set to 2000 and you spin 4 motors, each ESC will send feedback at 500hz, but if you only spin one motor, the ESC that is spinning will send feedback at thecmd-rate
. - here is an example of the most basic command that will set the
cmd-rate
to 2000, spin motor for for 5 seconds and plot the results (including rpm, power %, voltage, current).
./voxl-esc-spin.py --id 0 --cmd-rate 2000 --power 10 --timeout 5 --enable-plot 1
- please note that M0129 only measures total battery current that is flowing thru it (not individual), and only ID3 has the current sensor, so you need to test ID3 if you want the total current reported (it will print as
BOARD CURRENT
in your test script). M0134 ESC has individual current sensing for each ESC channel. - if you need the data logged to a file, you can use
--enable-logging 1
flag, and the ASCII log will be saved tologs
folder insidevoxl-esc-tools
directory, where you are running the test. The log format is a s follows:
PACKET_TYPE LINUX_TIMESTAMP_MS ESC_ID ESC_POWER (RESERVED) ACTUAL_RPM VOLTAGE CURRENT ESC_TEMPERATURE ESC_RCVD_COMMAND_COUNTER RESERVED RESERVED RESERVED
here is what a typical log entry looks like:
128 1722869479610 3 10 0 980 11.989 0.024 38.500 20 0 0 0
- the standard feedback packet type is 128, in this case the ID 3 is sending feedback, it is spun at power 10%, 980RPM, voltage is 11.989, current is 0.024A (no load spin), ESC temperature is 38.5 deg C
- if you use M0129, there will be additional packets in the log, with just voltage and current
- please note that if you use the logging option, the timestamp is saved in milliseconds, so if the feedback is coming back at a higher rate than 1khz, you could not tell the timestamps apart. I will fix this..
- one more tip, it helps to run the linux PC in performance mode in order to minimize the cpu delays / sleeps. The ESC feedback packets (currently) do not have the timestamp from the ESC itself, so the accuracy / jitter of the timestamp depends on how quickly the PC can wake up and send/receive the data.
- you can also modify the spin script to save the data in the format you need, but the log file is probably more reliable to make sure no data is missed.
Regarding PX4, on VOXL2, the ESC driver runs at 800hz (which is the update rate of the flight loop), each ESC sends feedback at 200hz. ESC status is published at that rate, but it may not logged at full rate to px4 log file, i would need to double check. Here is the code reference : https://github.com/modalai/px4-firmware/blob/voxl-dev/src/drivers/actuators/voxl_esc/voxl_esc.cpp#L1342
I know this is quite a lot of information, please let me know if you need any other clarification.
Alex
- make sure the ESC baud rate is set to 2Mbit (first make sure your usb-to-serial adapter can support it). here is an example esc param file showing the baud rate set to 2Mbit. It may already be set to 2Mbit for your esc, you can verify using