M0117 ESC rough control
-
Hello community,
I have been working with VOXL2 and M0117 VOXL ESC for controlling my custom drone. I started using this ESC when PX4 was on 1.12 version on VOXL2 old SDK. Then the drone used to fly nicely. This project was on pause for few months post which now I upgraded VOXL2 to latest SDK 1.1.2 and also M0117 to the latest available firmware which comes with SDK. Now the aircraft seems to be having extremely rough control where I can see motors struggling to keep aircraft in air and also occasionally maxing out as well as can be seen in the logs. This is the same motor, propeller and battery setup which worked beautifully on PX4 1.12 with old VOXL ESC firmware (I dont know the hash for that firmware version)Please check logs of my aircraft which shows unstable behaviour and also check the ESC configuration parameters. Btw I also caliberated the ESC again with propeller just to eliminate any issues from old parameters. I also successfully flashed and verified the parameters on all four ESC which went well.
Logs : https://review.px4.io/plot_app?log=fd6a4fdb-bc99-431b-b56d-b5288a3e6f91
ESC Parameters :
<?xml version="1.0" encoding="UTF-8"?> <!-- Copyright (c) 2020 ModalAI Inc. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 4. The Software is used solely in conjunction with devices provided by ModalAI Inc. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. For a license to use on non-ModalAI hardware, please contact license@modalai.com --> <EscParameters> <IdParams> <param name="id" value="127"/> <!-- 0-7 .. 127 means use hardware ID pins to read ID--> <param name="dir" value="2"/> <!-- 0=fwd, 1=rev, 2=fwd id-based, 3=rev id-based --> </IdParams> <UartParams> <param name="protocol_version" value="2"/> <!-- reserved for future use --> <param name="input_mode" value="0"/> <!-- reserved for future use --> <param name="baud_rate" value="250000"/> <!-- communication bit rate --> <param name="char_timeout_ns" value="0"/> <!-- not used --> <param name="cmd_timeout_ns" value="100000000"/> <!-- timeout for incoming commands before ESC will stop the motor --> </UartParams> <TuneParams> <param name="pwm_frequency" value="48000"/> <!-- switching freqency of PWM signal going to motors. 24Khz and 48Khz are only options for now --> <param name="vbat_nominal_mv" value="14800"/> <!-- used for sanity checking and limiting of voltage-dependent funcions --> <param name="num_cycles_per_rev" value="12"/> <!-- number of pole pairs in the motor. used for converting electrical frequency to mechanical rpm --> <param name="min_rpm" value="200"/> <!-- minimum RPM that will be attempted, otherwise capped --> <param name="max_rpm" value="25000"/> <!-- maximum RPM that will be attempted, otherwise capped --> <param name="min_pwm" value="50"/> <!-- cap for minimum power to be ever applied. max is 999 --> <param name="max_pwm" value="999"/> <!-- cap for maximum power to be ever applied. max is 999 --> <param name="pwm_vs_rpm_curve_a0" value="643.33705555"/> <!-- this is actually motor_voltage vs rpm curve.. using legacy naming --> <param name="pwm_vs_rpm_curve_a1" value="0.762820572544"/> <!-- Emax RS1306 3300KV with tri-blade 3x3x3 --> <param name="pwm_vs_rpm_curve_a2" value="0.000110277717331"/> <param name="kp" value="0"/> <!-- RPM controller proportional gain --> <param name="ki" value="0"/> <!-- RPM controller proportional gain --> <param name="max_kpe" value="00"/> <!-- maximum proportional erorr term (max is 999) --> <param name="max_kie" value="00"/> <!-- maximum integral error term (max is 999) --> <param name="max_rpm_delta" value="3000"/> <!-- cap for maximum rpm error used in RPM controller --> <param name="spinup_type" value="0"/> <!-- 0: traditional, 1: sinusoidal --> <param name="spinup_power" value="250"/> <!-- power used to during spin-up procedure --> <param name="latch_power" value="80"/> <!-- power used during latching stage of spin-up (out of 999)--> <param name="spinup_power_ramp" value="1"/> <!-- it will take ( 4096 / (spinup_power_ramp*10000) ) seconds to ramp sinusoidal start-up power from 0 to spinup_power --> <param name="spinup_rpm_target" value="1000"/> <!-- Desired RPM at the end of the sinusoidal spin-up procedure --> <param name="spinup_time_ms" value="1000"/> <!-- Duration of the sinusoidal spin-up procedure --> <param name="spinup_bemf_comp" value="1"/> <!-- 0: disable, 1:enable back-emf compensation in sinusoidal spin-up procedure --> <param name="motor_kv" value="1500"/> <!-- kV value of the motor. used in back-emf compensation during spin-up --> <param name="min_num_cross_for_closed_loop" value="50"/> <!-- exit latching mode of fixed power after this number of zero crossings --> <param name="protection_stall_check_rpm" value="1000"/> <!-- if motor spins below this RPM, stall check will trigger and stop / restart the motor --> <param name="brake_to_stop" value="0"/> <!-- apply brake when stopping motor (or not) --> <param name="stall_timeout_ns" value="20000000"/> <!-- after spin-up, if no zero crossing is not detected for this amount of time, motor is considered stalled --> <param name="require_reset_if_stalled" value="0"/> <!-- require sending an array of zero commands to reset before next spin-up, if motor stalled --> <!-- The Entertainer --> <param name="tone_freqs" value="[118, 132, 105, 88, 99, 88, 83, 78, 1, 235, 0, 0]"/> <!-- 200 is 2000Hz, max 255 --> <param name="tone_durations" value="[30, 30, 30, 60, 30, 30, 30, 60, 60, 60, 0, 0]"/> <!-- duration of each tone in units of 10 milli-seconds. Poor naming!!! --> <param name="tone_powers" value="[100, 100, 100, 100, 100, 100, 100, 100, 0, 100, 0, 0]"/> <!-- max is 255 --> <param name="dt_threshold_ns" value="150000"/> <!-- during start up, ignore inter-commutation times less than this val, probably noise --> <param name="max_dt_ns" value="2500000"/> <!-- min and max values for time between two commutations. these are used as caps --> <param name="min_dt_ns" value="10000"/> <param name="dt_bootstrap_ns" value="2000000"/> <!-- filter bootstrap value for commutation dt during start up --> <param name="spinup_stall_dt_ns" value="60000000"/> <!-- during spin-up, if no zero crossing is not detected for this amount of time, motor is considered stalled --> <param name="spinup_stall_check_ns" value="30000000"/> <!-- time after beginning of spinup to start checking for spinup stall --> <param name="alignment_time_ns" value="0"/> <!-- alignment time before spin-up --> <param name="timing_advance" value="0"/> <param name="sense_advance" value="0"/> <param name="demag_timing" value="0"/> <!-- unused --> </TuneParams> </EscParameters>
ESC firmware version :
Firmware hash : eb6fb500
Bootloader hash : 25317f42
Mo117-1 ESC firmwareI am using Tmotor F2203 motor 1500 kv with 5 inch propeller. Also I am using 4S battery.
Does my ESC configuration file looks correct for given motors?
Please help debug this ahead. -
Please have a look at RPM plots of my UAV while in air. There seems to be lots of fluctuations.
-
@Aaky , There are a few issues with your ESC parameters. I can help you - if you tell me which 5" propeller you are using, i can test it on this motor (which I have) and provide the params to you.
-
Specifically, here is the list of issues with the esc params file:
num_cycles_per_rev
should be set to number of pole pairs, which is 7 for your motor (not 12!)min_rpm
seems wrong, it cannot be 200RPM for your motor, maybe 2000 ?- 'max_rpm' - did you test to make sure the motor can reach 25K rpm with this propeller? This is not a critical parameter, but it can be misleading to you and if you use it in PX4 params, it can lead to issues if the RPM cannot actually be achieved
pwm_vs_rpm_curve_a0
,a1
,a2
- did you actually calibrate your motor / prop?spinup_power
is too high, usually around100
is enough- you should use sinusoidal spinup,
spinup_type = 1
,spinup_power
= 100 - 120,spinup_power_ramp
=8, - the proportional and integral control is disabled, i assume you did this on purpose
In any case, if you would like to provide the details of the propeller, i can help you tune the motor.
-
@Alex-Kushleyev Thanks Alex for the information.
My propeller configuration is 6x4x3 as shown on this link. Please let me know if you can provide the tune.I will correct my num_cycles_per_rev parameter also min and max rpm.
Strange part is, last year when I tested my drone with these parameters it worked well around June 2023 was the timeline.
I actually caliberated pwm_vs_rpm_curve_a0, a1, a2 with propeller on motor and got those values in above xml files.
@Alex-Kushleyev said in M0117 ESC rough control:
the proportional and integral control is disabled, i assume you did this on purpose
How do we tune propotional and integral control? Please provide a tuning guide for these parameters.
-
@Aaky , thank you for providing the details. Actually, I do have this exact propeller, so I will be able to help you very soon.
I will recommend to leave the kp and ki parameters disabled until you have a stable flight. Having aggressive response in ESC is not always a good thing, especially if you have a lot of gyro noise, so it's best to start with a soft ESC response and experiment with higher gains later.
Let me get back to you after the weekend. Meanwhile, please read this document carefully and go through the tuning procedure : https://gitlab.com/voxl-public/voxl-sdk/utilities/voxl-esc/-/blob/master/voxl-esc-tools/calibration.md . Leave the kp and ki terms zero for now.
For spinup params, please try these:
<param name="spinup_type" value="1"/> <!-- 0: traditional, 1: sinusoidal --> <param name="spinup_power" value="120"/> <!-- power used to during spin-up procedure --> <param name="latch_power" value="80"/> <!-- power used during latching stage of spin-up (out of 999)--> <param name="spinup_power_ramp" value="8"/> <!-- it will take ( 4096 / (spinup_power_ramp*10000) ) seconds to ramp sinusoidal start-up power from 0 to spinup_power --> <param name="spinup_rpm_target" value="2000"/> <!-- Desired RPM at the end of the sinusoidal spin-up procedure --> <param name="spinup_time_ms" value="1000"/> <!-- Duration of the sinusoidal spin-up procedure --> <param name="spinup_bemf_comp" value="1"/> <!-- 0: disable, 1:enable back-emf compensation in sinusoidal spin-up procedure --> <param name="motor_kv" value="1500"/> <!-- kV value of the motor. used in back-emf compensation during spin-up -->
spinup_rpm_target
you could set more accurately to the value that your motor+prop spin at about 10% power (you can test this usingvoxl-esc-spin.py
test command). This way, the target RPM of the spinup procedure will be roughly the idle RPM at minimum power.Also, please double check your PX4 tuning parameters and make sure they have not changed from the last time you had good flight.
Alex
-
@Alex-Kushleyev Sure Thanks Alex. Will follow this procedure for our current tests. Regarding calibration part, We generally do something like putting propeller in reverse direction where air is pushed upwards and not downwards and then run voxl-esc-calibration script. This also should yield good results for a0,a1 and a2 parameters to be derived?
-
@Alex-Kushleyev Following up over my query. If you have good tune and how you achieved it with the above mentioned motor and propeller set, please let me know.
-
@Aaky , yes, sorry for the delay. I have been working on this and should have an update for you this evening with a parameter file and some plots.
Alex
-
@Aaky , I just posted the ESC param file here :
- https://gitlab.com/voxl-public/voxl-sdk/utilities/voxl-esc/-/blob/dev/voxl-esc-params/misc/esc_params_tm_2203_5_1500kv_6042_3.xml -- all my final recommended settings are in this file, below you will find some explanations.
I used the latest ESC firmware for M0117 ESC :
All tests were performed on a ID 0 of the 4-in-1 ESC.
Calibrations results are nice and smooth:
./voxl-esc-calibrate.py --id 0
Feed forward params from calibration:
<param name="pwm_vs_rpm_curve_a0" value="338.4975"/> <param name="pwm_vs_rpm_curve_a1" value="0.51777"/> <param name="pwm_vs_rpm_curve_a2" value="3.56026e-05"/>
Ramp from 10 to 100% power at full battery (16.5V) - also nice and smooth.
./voxl-esc-spin.py --id 0 --power 100 --ramp-time 2.0 --timeout 3.5 --init-cmd 10 --init-time 1.0 --cmd-rate 2000 --enable-plot 1
Maximum RPM (I set 15K in ESC params as absolute max), you may want to limit in PX4 because at discharged battery, 15K rpm cannot be achieved
- 13800 RPM @ 14.2V, 14.7A
- 14900 RPM @ 16.1V, 17.5A
I set the sinusoidal spin-up params to target 2000 rpm (which is about the minimum rpm at 10% power) and it will take 1 second to spin up. If you want to spin up faster if you can do that and maybe also increase the
spinup_power
from 110 to 130 if you choose faster spinup. Sometimes, spinning up too fast at lower power can loose sync.protection_stall_check_rpm
param has been set to 1000RPM which is half of the minimum RPM.Step tests using the following command (running on PC, so high command rate for more data):
./voxl-esc-spin-step.py --id 0 --init-time 1.0 --init-cmd 3000 --rpm 3000 --step-amplitude 4000 --timeout 3.0 --enable-plot 1 --cmd-rate 2000
- RED : kp = 0, ki = 0 (only feed-forward term is enabled)
- GREEN : kp = 50, ki = 5, max_kpe = 100, max_kie = 50
- BLUE : kp = 100, ki = 15, max_kpe = 200, max_kie = 100
- Interpretation of this plot:
- RPM response of RED plot (kp,ki = 0) is considerably slower than others
- with kp = 50 and kp = 100, you see significantly larger current spikes during the upward transition
- kp=50 is significantly faster than kp=0, but kp=100 is not much faster than kp=50, although uses noticeably more current, which may mean that the motor torque saturates and not able to produce higher torque with higher current.
The final configuration (as committed), i suggest the following. If you want softer response, you can drop kp and ki to
zero
and work on PX4 tuning, and then later if you want faster ESC response, set back to these. Please note that if you have a lot of gyro noise, it will result in noisy RPM commands and aggressive ESC response will try to track noisy RPM commands and can make the vehicle shake and make things worse. I would not say that my final params are too "aggressive", but the response is pretty fast and very smooth. The rest depends on your PX4 params and gyro noise<param name="kp" value="50"/> <!-- RPM controller proportional gain --> <param name="ki" value="5"/> <!-- RPM controller proportional gain --> <param name="max_kpe" value="100"/> <!-- maximum proportional erorr term (max is 999) --> <param name="max_kie" value="50"/> <!-- maximum integral error term (max is 999) --> <param name="max_rpm_delta" value="8000"/> <!-- cap for maximum rpm error used in RPM controller -->
Two final recommendations:
- keep an eye of ESC temperature (which is saved in PX4 logs). it helps to review the temps after first few flights to make sure they are staying in the <80 C range. (100C+ would be too high), 50-60 is ideal. You can try to keep the ESC open to the air flow from the propellers and should be OK.
- You may consider adding an electrolytic capacitor to the ESC power pads if you are going to try aggressive flights, it should help keep the ESC performance smooth.
Please let me know if you have any more questions.
Alex
-
@Alex-Kushleyev Thanks Alex for such a detailed response and explanation. I will flash the parameters and check the response in flight and get back to you over this. Thank you once again!
-
@Aaky , you are welcome. Also, i wanted to note that i have tested these params in very extreme case where rpm steps are between 2000 and 15000 rpm (worst case scenario) using the following command:
./voxl-esc-spin-step.py --id 0 --init-time 1.0 --init-cmd 2000 --rpm 2000 --step-amplitude 13000 --timeout 3.0 --enable-plot 1
The response was stable, see the plot below. Obviously very high current, reaching 40A during peak (for just a single motor).
Also, you asked about running the ESC calibration with propeller reversed (blowing air down). It is an interesting idea and it should work, but I do not recommend it due to safety reasons. When I run the calibration, the motor is always rigidly attached to a solid structure, whether it is just a standalone arm with just one motor / prop or if I am using the whole drone, i find a way to mechanically fix it to a work bench or something heavy (depending on circumstances). Also being close to the ground, calibration could be slightly affected by the ground effect / high air disturbance, but the main factor to consider is safety.
2000-15000 RPM Step Results:
-
@Alex-Kushleyev Thanks Alex. Graphs look good. I am yet to stress test with these parameters but I was able to takeoff my drone with these parameters and it seemed to be very smooth. Will perform more tests in upcoming days and get back to you.
-
@Alex-Kushleyev I had one general query. I am using in one of my drone VOXL2 IO with Tmotor ESC with recent Oneshot Build which you shared with me previously.
Below are my queries.- If I want to compare VOXL2 ESC 4 in 1 with VOXL2 IO + Tmotor ESC setup what would yield better results? I understand we have some closed loop control with VOXL2 4-in-1 ESC as compared to VOXL2 IO based setup but is this closed loop control actually functional in flight and more better for aircraft under 3 kg weight category? Also is there a way to loop back ESC telemetry from Tmotor like ESC to PX4 on any of its UART ports with voxl-px4 firmware? Can that help apart from diagnostics?
- I have worked with Arducopter firmware where ESC telemetry helps to identify and track harmonic notches improving overall tuning results, have you heard of anything like that in PX4? (This is PX4 specific query I understand but just wanted to check if I can do any better with Tmotor like ESC providing telemetry back to PX4)
- Does VOXL ESC controls motors in closed loop by detecting RPM/Power while PX4 is commanding drone in Position flight mode?
-
@Aaky , Please see below answers to your questions
- Whenever you are using any of the VOXL ESCs in PX4, they are always doing closed-loop RPM control. The ESCs themselves are capable of operating on "open loop" mode, similar to traditional ESCs and that can be tested using
voxl-esc
tools (we refer to it aspower
control as opposed torpm control
. The RPM closed loop control is always active in flight. We do not support telemetry using VOXL2 IO board - if you want detailed telemetry from ESCs, you should use ModalAI ESCs, which provide, voltage, current, rpm, esc temperature, applied % power, each at 200Hz (while flight control loop is running at 800hz). This data is already available and being logged to px4 logs (although not at such a high rate, which could be modified on the px4 side). The ESC information is published viaesc_status
topic.
Closed loop control, when tuned properly, provides superior (over open loop) behavior and that is why we use it. Not only the control is accurate, it is also generally faster (depending on your PI gains in ESC params). The speed of ESC response becomes more important as vehicle gets smaller - this is because smaller vehicles have faster dynamics and can benefit more from faster motor response. With large vehicles, their large moment of inertia may prevent fast ESCs from providing any benefit. I already shared some plots above in this thread that show you how much difference in response time the proportional control can make.
-
I am not sure about PX4 features that track "harmonic notches improving overall tuning results". However, the ModalAI ESC does RPM control and provides RPM feedback, so this information can be used for filtering out vibrations (I believe that this is what you are referring to). Beyond this, I cannot provide any more guidance as we have not used such features in PX4.
-
In all flight modes, if you use ModalAI ESC with PX4, closed loop RPM control is used.
If I were to summarize the benefit of closed loop ESC control vs closed loop RPM control in one statement, it would be something like this.. For small vehicles, in absence of excessive vibrations, the faster closed loop RPM control should allow you to increase your attitude control (roll, pitch, yaw) gains in your flight controller (PX4), which means you can achieve more accurate flight.
If you have more questions, please let me know.
Alex
- Whenever you are using any of the VOXL ESCs in PX4, they are always doing closed-loop RPM control. The ESCs themselves are capable of operating on "open loop" mode, similar to traditional ESCs and that can be tested using
-
@Alex-Kushleyev Thanks for detailed response Alex. I am currently using this ESC from Tmotor. This ESC is running with BLHeli32 firmware. Any idea if this has closed loop RPM control? Since this ESC provides telemetry feedback I am guessing it has some closed loop control but I dont know if I can tune its response with any PI parameters as that of VOXL ESC. Let me know if you have any information.
Reason behind all these queries is I have custom drone with VOXL2 IO and above shown Tmotor ESC. I have tried manual and Autotuning the aircraft, well it flies but while I fly it in indoors it dosent seem to be accurately holding its posiiton and keeps moving around 10-15 cms in horizontal axis. Also the yaw control is not very stable and aircraft wobbles in the interim mildly and again becomes stable. I am just checking is improving ESC going to solve my problems.
-
@Aaky , as far as I know, BLHeli32 does not do closed loop RPM control, however it can report the RPM feedback (similar to how VOXL ESC is doing). the DShot protocol supports requesting telemetry, which is sent back to the flight controller via UART. In this configuration, there are 4 Dshot signals going from the flight controller and 1 UART TX coming back from the ESC into the Flight controller.
There is also a different telemetry option, where the ESC sends back telemetry sign the dedicated PWM / Dshot wires (same wires used to send Dshot commands from FC to ESC are used by ESC to send telemetry back to FC). The latter is called "dshot telemetry" and it can be sent at a much higher rate because each ESC has a dedicated signal line.
I believe Betaflight and maybe Arducopter can the Dshot telemetry for tracking what RPMs the motors are spinning and apply dynamic notch filters to try to filter out vibrations that are coming from all 4 motors.
You can find more information about dshot and telemetry here : https://brushlesswhoop.com/dshot-and-bidirectional-dshot/
What I would recommend, if it is possible for you, keep the current drone with VOXL2 IO and tmotor ESC and build another (identical) drone with the ModalAI ESC. Then you can test them side by side and compare flight performance with similar FC tuning and everything else being the same. It will be faster than swapping ESCs between the tests.
Alex
-
@Alex-Kushleyev Thanks Alex for alll the details. I will look into the test setup. What is the maximum continous current limit for this VOXL ESC? We have this ESC but not sure if it can replace Tmotor ESC specified in above link. Also what is maximum continuous current supported by this voxl esc? It is written 10A but upto what limits it is tested in miminal airflow conditions?
-
@Alex-Kushleyev Additionally,
Few stats from our motor : Our motor at hover time consumes 7.6 Amp and motor's peak current is at 18A. Current eventually increases as battery voltage decreases pushing hover current to 11A per motor.
Can this requirements be met with VOXL ESC 4-in-1 as linked above?
-
@Aaky , what is the voltage? 4S or 6S?
M0117 s M0134 escs can handle more than 10A continuous but with proper cooling. It has to be tested in your conditions to be sure. Monitor the esc temperature and stop the test immediately if esc temp gets above 100-110 C. Ideally, esc should be in the 50-80C range.
If you have an M01117 already, you could use that for testing if voltage is 4s or lower.
Also it seems your motor power may be a bit insufficient, if at hover you could have 11A at low battery, but absolute max current is 18A (i assume charged battery). The motor may be operating with little margin (low thrust to weight ratio of the drone). Please check!