Modifying Iris Motor Parameters in SITL (ArduPilot + Gazebo) – Changes Not Taking Effect

Hello everyone,

I’m running ArduPilot SITL with the iris_with_gimbal Gazebo model that exist in the rapo ardupilot_gazebo and trying to tweak the motor dynamics so they better match my real quadcopter. I’ve successfully adjusted the masses in the SDF of the base model iris_with_standpffs, but I can’t seem to get any of my motor parameter changes to apply.


What I’ve tried

  1. Location of the plugin
    I located the motor‐model plugin in the ArduPilot source tree under:
ardupilot/
  libraries/SITL/examples/Json/pybullet/models/iris.urdf

couldnt find a plugin in the repo ardupilot_gazebo but im guessing it just use the regular ardupilot!

  1. Example plugin snippet
    Here is the snippet I’m editing in iris.urdf:
<plugin filename="librotors_gazebo_motor_model.so" name="iris_front_right_motor_model">
  <robotNamespace>iris</robotNamespace>
  <jointName>iris/rotor_0_joint</jointName>
  <linkName>iris/rotor_0</linkName>
  <turningDirection>ccw</turningDirection>
  <timeConstantUp>0.0125</timeConstantUp>
  <timeConstantDown>0.025</timeConstantDown>
  <maxRotVelocity>2262</maxRotVelocity>
  <motorConstant>4.7e-6</motorConstant>
  <momentConstant>0.02</momentConstant>
  <commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
  <motorNumber>0</motorNumber>
  <rotorDragCoefficient>1.2e-04</rotorDragCoefficient>
  <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
  <motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>
  <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
  1. Build & run
    After editing, I run:
cd ~/ros_ws
colcon build
source install/setup.bash

and then start SITL:

ros2 launch ardupilot_gz_bringup iris_runway.launch.py

Despite modifying values like <motorConstant> and <maxRotVelocity>, the simulation behavior remains identical to the defaults.

What can be the cause?
Am i compiling it the right way, or it is not the location?

Try running the basic iris model using the instructions in the ardupilot_gazebo README.

The librotors_gazebo_motor_model.so is for Gazebo Classic which is EOL and no longer supported. The motor parameters for the iris_model in this example can be found in the iris_with_ardupilot model.

It’s not necessary to run ROS for a basic ArduPilot SITL / Gazebo session. If ROS is required then the ros2 branch of ardupilot_gazebo is required to ensure the models can be loaded in rviz2 and other tools. The model definition may be in ardupilot_gazebo, or in ardupilot_gz, depending on the launch configuration.