Hi,
Background: I’m working on SITL simulation for an inverted coaxial drone using PX4 v1.15 with gz-harmonic and ROS2 Humble. I’ve implemented a custom airframe configuration and control allocation, and I’m using ROS2 to publish thrust and torque setpoints to the flight controller.
Problem: I believe I’ve found a bug in the GZ bridge ESC interface related to parameters SIM_GZ_EC_MAX
and SIM_GZ_EC_MIN
.
From my understanding, PX4 publishes normalized PWM values from control allocation via actuator_motor.msg
. The mixer module then scales these values between SIM_GZ_EC_MIN
(e.g., 0) and SIM_GZ_EC_MAX
(e.g., 1000). However, the issue is that these interpolated values (0-1000 range) are incorrectly being published to gz-sim as velocity commands on the actuators.proto
topic. In reality, this new scaled value doesn’t represent anything meaningful.
Code Reference: PX4-Autopilot/src/modules/simulation/gz_bridge/GZMixingInterfaceESC.cpp at 99c40407ffd7ac184e2d7b4b293f36f10fe561ef · PX4/PX4-Autopilot · GitHub
Has anyone else encountered this, or can someone confirm if this is the intended behavior?
Thank you.
I’m not sure. @Jaeyoung-Lim might know
@yash_agarwal @dakejahl It is intentional that it does not represent anything, but it is slightly half baked in the sense that we don’t know what interface we do want.
The main problem is that there is no good model for an ESC. 3-phase ESCs are not RPM controlled, and thrust may depend not only the input but also many other factors such as the vehicle’s state.
Gazebo classic, used to have a simulated PWM interface, since PX4 was using mixers that were based on pwm outputs. This soon got too complicated and unnecessary, since all it was doing was rescaling and adding offsets.
The new GZ ESC interface was an attempt to simplify this interface where now it is always just scaled to something around 1000. What is slightly not elegant is probably how this translates to rotor velocity or thrust. However, this conversion is currently consumed into the model parameters (e.g. rotor thrust coefficient).
I am all in for making the interface more “realistic”, if you would be interested in improving the interface. However, with the condition that it is easy to identify the parameters of the real vehicle in order to link it back to the simulated model. Otherwise people will just use random values that match the scale, which is just as inaccurate as what we have already.
@Jaeyoung-Lim, thanks for your insights on this topic.
You’re absolutely right that thrust prediction is extremely challenging due to its dependence on vehicle state and aerodynamic effects, particularly at high velocities.
As you mentioned, Gazebo-classic PWM interface has scaling and offsets to map PWM to motor speeds, while, in GZ ESC interface there is only a scaling part of normalized PWM values. While both approaches rely on linear interpolations, Gazebo-classic PWM interface has more in common with actual hardware interface and is more intuitive.
However, real-world ESC behavior is rarely linear. In practice, the relationship between PWM signals and motor speeds is better represented by higher-order polynomials—typically quadratic for unidirectional motors and cubic for bidirectional motors.
One of the way to make GZ ESC interface to be more accurate, intuitive and more similar to hardware is to provide a cubic polynomial for each motor in GZ ESC interface to map PWM in range [1000,2000] to rotor speed, whose coefficients can be set through params in GZbridge module.
Below is a code snippet on how can GZ ESC can be modified.
bool GZMixingInterfaceESC::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs,
unsigned num_control_groups_updated)
{
unsigned active_output_count = 0;
for (unsigned i = 0; i < num_outputs; i++) {
if (_mixing_output.isFunctionSet(i)) {
active_output_count++;
} else {
break;
}
}
if (active_output_count > 0) {
gz::msgs::Actuators rotor_velocity_message;
rotor_velocity_message.mutable_velocity()->Resize(active_output_count, 0);
for (unsigned i = 0; i < active_output_count; i++) {
// Convert [0,1000] to [1000, 2000] range
_modified_outputs[i] = outputs[i] + 1000.0f;
// Map PWM to motor speed using the quadratic polynomials
_motor_speed[i] = _pwm_2_motor_speed_coeff[0] * (_modified_outputs[i] * _modified_outputs[i]) +
_pwm_2_motor_speed_coeff[1] * _modified_outputs[i] + _pwm_2_motor_speed_coeff[2];
rotor_velocity_message.set_velocity(i, _motor_speed[i]);
}
if (_actuators_pub.Valid()) {
// Publish the rotor velocity message on PX4 for debugging
GZMixingInterfaceESC::motorSpeedPublish(active_output_count);
// Reset the modified outputs and motor speeds
for (unsigned i = 0; i < active_output_count; i++) {
_modified_outputs[i] = 0.0f;
_motor_speed[i] = 0.0f;
}
return _actuators_pub.Publish(rotor_velocity_message);
}
}
return false;
}
Thanks
@yash_agarwal Thank you for your suggestion.
-
I would refrain from using [1000,2000] which is connecting the interface to PWM again. The main thing is that PWM is not the only interface that PX4 supports as an ESC interface. There are also serial interfaces such as UAVCAN. The thinking here was we should define the simulated ESC interface as its own interface, addition to PWM and UAVCAN. Therefore, I would want to make it directly related to [-1, 1], [0, 1]. (This is on my todo list).
-
I like the suggestion on using a cubic spline; But what I am a little concerned is the added complexity. The “accuracy” is only there if the spline is fitted for your model. With the current model, it is easy to identify the motor constants around your hover point. However, if the spline is added, there are more parameters that you need to identify which may or may not be observable in your flight data. Therefore, there needs a way to identify the spline parameters. Otherwise we are adding complexity on representing the model as a more accurate in the functional form, but not in the actual thrust prediction.
-
This should be part of the gazebo_motor_plugin. The reason the rotor velocity is published is because the default motor_model_plugin in gazebo consumes that, not because we are mindfull of the rotor models itself.
If you can show that your suggestion improves the simulation accuracy with real data, I will be happy to incorporate the changes. However, I would be a bit more mindful on adding complexity for the “theoretical” accuracy.
We are testing software with SITL, and the dynamics should be tuned to best do that.