I have made a custom gazebo-classic sitl model for a heavy UAV by customizing the iris model. Airframe is coaxial octorotor as per PX4 airframes reference terminology. The UAV has a total weight of 250 kg. I have calculated the parameters for the 8 electric motors required by the gazebo motor plugin as below:
Ω Rotor angular velocity [rad/s]: 230.697
Motor Constant: 0.018166
Moment Constant: 0.078038
Rotor Drag Coefficient: 0.095973
Rolling Moment Coefficient: 1.00E-06
I have done all necessary changes for the sdf file in gazebo side and also for the airframe in px4 side. The simulation with px4 sitl gazebo runs well and the UAV is able to takeoff, however a few seconds after takeoff the drone climbs unresponsively to the sky and it is not possible to control it other than killing it.
I have tested many cases and it seems for motor constant values above a certain value, the simulation is showing this type of uncontrolled climb after takeoff.
Does anyone have similar experience with px4 sitl gazebo for heavy drones?
Is there an upper limit of UAV weight for px4 gazebo sitl simulation which above that it cannot handle the simulation?
Any help on this issue will be appreciated.
As you see, the drone takes off at around 30% of RC throttle and is stable, but after a few seconds, it climbs up although I bring down the throttle to zero.
The value of required thrust that the px4 log shows is a very small value at takeoff and even after climb. The start of unresponsive climb is at the moment when the thrust jumps which as per my investigation is a result of jump (almost getting doubled) in motors velocity. I do not know why and where that spike in the velocity happens and how to fix it!
Thank you Julian.
I see that, but why the motors are that much powerful although I used corresponding parameters in the motor plugin? Do you see any error in the gazebo motor plugin parameters that I mentioned above?
The thrust to weight ratio here is around 3. It is bigger than the recommended value of 2 but not unrealistic. Even with higher weight (lower thrust/weight ratio), I get the same unresponsive climb!
I followed formulas from these sources to calculate motor plugin parameters:
Hi Julian,
Any ideas on my last question? @JulianOes
I also double checked the parameters I used for the gazebo motor plugin in the sdf file and they all seem to be correct. Even I put logging code in the gazebo motor plugin to print the real-time values of velocity, force, and moment for each rotor on the terminal and everything look physically reasonable on the Gazebo side. I do not see any big or unrealistic force, velocity or moment from the motors! Here you see the forces values in newton after arming.
My guess is that some estimations on the PX4 side are making the motors way more powerful than what they are defined in the sdf file. Any help or comment is appreciated.
I would be surprised if the motor plugin in gazebo actually makes sense in terms of physics. From what I know the numbers are usually tweaked trial and error until hover thrust is around 50% and it works.
That being said, if you find what’s wrong or can fix it, that would be great, just don’t assume things are correct.
So if it is only tweaking motor parameters to get 50% hover thrust, do you mean that it is not possible to model powerful motors (with around 90kgf of max thrust) by Gazebo motor plugin to an acceptable level of accuracy?
Hi Julian,
I tried to tweak the motor parameters to get 50% hover thrust but PX4 cannot get to that! For example, with a thrust to weight ratio of only 1.3, I am still getting hover thrust of around 10%!!(I decreased the minimum thrust to 5% to avoid the forced climb I was facing before) Here is the screenshot from mavlink inspector in QGC at hovering which shows only around 10% of thrust is used (pwm signals around 1100)!
It seems that the motor signal is estimated and applied incorrectly by the controller on the PX4 side! Do you have any comment on how I can get to 50% of hovering throttle?
Hi Julian, I found the solution for this.
As the motors are much powerful than the common motors in the Gazebo sitl models (like iris) the default values for the gazebo mavlink interface (input_offset, input_scaling, zero_position_armed, and zero_position_disarmed) in the sdf file that scale and offset the control signal to get the motor velocity in the gazebo_mavlink_interface plugin are causing very small pwm signals. That’s why even with tweaking the motor parameters for the gazebo motor model, we cannot get appropriate throttle for hover for this heavy drone.
I used new values for the input_offset, input_scaling, zero_position_armed, and zero_position_disarmed and I could get 50% throttle at hover.
Even with using custom formula for motor speed in terms of signal I could model the motors with higher precision.
Thank you for all your comments and hints
Hi everyone, I’m encountering the same issue while working in Gazebo Harmonic. It seems that there’s no Mavlink plugin available, and the new versions are using MicroXRCE. Can someone guide me on how to modify these parameters? Any assistance would be greatly appreciated.
It appears there may be a misunderstanding or misuse of the Gazebo motor model plugin parameters. Specifically, the “maxRotVelocity” parameter, which is described as the “Maximum rotational velocity command in units of rad/s”, seems to be leading to unintended results in the thrust calculation.
The thrust force is computed using the following equation:
Consequently, at full throttle, the resulting force calculation is:
(maxRotVelocity * 10)^2 * motorConstant.
Based on my calculations, the resulting force in Gazebo appears significantly higher than expected. I am uncertain if I am misinterpreting a specific aspect of the model or if there is an issue with the parameter setup. Any guidance or insight into this discrepancy would be greatly appreciated.
Hello,
There is no misuse of the parameters in the motor plugin. The “rotorVelocitySlowdownSim” is only used to lower the rotor spin rate, particularly for small fast props, within the Gazebo simulation. It is not affecting the value of the force. See the whole plugin code not just part of it.
Try to adjust the gazebo mavlink interface parameters (input_offset, input_scaling, zero_position_armed, and zero_position_disarmed) in your sdf file. That might solve your issue
As I mentioned earlier, it seems that there are no MAVLink interface parameters in the new Gazebo Harmonic. The problem appears to be similar to yours, but the solution is different.