Hello,
I’m trying to replace the LiftDrag plugin with the MulticopterMotorModel plugin.
To do this, I switched to Gazebo Garden, ardupilot_gazebo ( 0753b06 ), Arducopter 4.5.7.
My SDF model:
<?xml version='1.0'?>
<sdf version="1.6">
<model name="iris_with_ardupilot">
<include>
<uri>model://iris_with_standoffs</uri>
</include>
<!-- plugins -->
<plugin filename="gz-sim-joint-state-publisher-system"
name="gz::sim::systems::JointStatePublisher">
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<robotNamespace></robotNamespace>
<jointName>iris_with_standoffs::rotor_0_joint</jointName>
<linkName>iris_with_standoffs::rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1381</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>/model/iris_with_standoffs/rotors/cmd_vel</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/model/iris_with_standoffs/rotors/speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<robotNamespace></robotNamespace>
<jointName>iris_with_standoffs::rotor_1_joint</jointName>
<linkName>iris_with_standoffs::rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1381</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>/model/iris_with_standoffs/rotors/cmd_vel</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/model/iris_with_standoffs/rotors/speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<robotNamespace></robotNamespace>
<jointName>iris_with_standoffs::rotor_2_joint</jointName>
<linkName>iris_with_standoffs::rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1381</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>/model/iris_with_standoffs/rotors/cmd_vel</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/model/iris_with_standoffs/rotors/speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<robotNamespace></robotNamespace>
<jointName>iris_with_standoffs::rotor_3_joint</jointName>
<linkName>iris_with_standoffs::rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1381</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>/model/iris_with_standoffs/rotors/cmd_vel</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/model/iris_with_standoffs/rotors/speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin name="ArduPilotPlugin"
filename="libArduPilotPlugin">
<!-- Port settings -->
<fdm_addr>127.0.0.1</fdm_addr>
<fdm_port_in>9002</fdm_port_in>
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<lock_step>1</lock_step>
<have_32_channels>0</have_32_channels>
<!-- Frame conventions
Require by ArduPilot: change model and gazebo from XYZ to XY-Z coordinates
-->
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
<!-- Sensors -->
<imuName>iris_with_standoffs::imu_link::imu_sensor</imuName>
<!--
incoming control command [0, 1]
so offset it by 0 to get [0, 1]
and divide max target by 1.
offset = 0
multiplier = 838 max rpm / 1 = 838
-->
<control channel="0">
<jointName>iris_with_standoffs::rotor_0_joint</jointName>
<useForce>1</useForce>
<multiplier>838</multiplier>
<offset>0</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/model/iris_with_standoffs/joint/rotor_0_joint/cmd_vel</cmd_topic>
<!-- <type>VELOCITY</type>
<p_gain>0.20</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>2.5</cmd_max>
<cmd_min>-2.5</cmd_min>
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim> -->
</control>
<control channel="1">
<jointName>iris_with_standoffs::rotor_1_joint</jointName>
<useForce>1</useForce>
<multiplier>838</multiplier>
<offset>0</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/model/iris_with_standoffs/joint/rotor_1_joint/cmd_vel</cmd_topic>
<!-- <type>VELOCITY</type>
<p_gain>0.20</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>2.5</cmd_max>
<cmd_min>-2.5</cmd_min>
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim> -->
</control>
<control channel="2">
<jointName>iris_with_standoffs::rotor_2_joint</jointName>
<useForce>1</useForce>
<multiplier>-838</multiplier>
<offset>0</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/model/iris_with_standoffs/joint/rotor_2_joint/cmd_vel</cmd_topic>
<!-- <type>VELOCITY</type>
<p_gain>0.20</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>2.5</cmd_max>
<cmd_min>-2.5</cmd_min>
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim> -->
</control>
<control channel="3">
<jointName>iris_with_standoffs::rotor_3_joint</jointName>
<useForce>1</useForce>
<multiplier>-838</multiplier>
<offset>0</offset>
<servo_min>1100</servo_min>
<servo_max>1900</servo_max>
<type>COMMAND</type>
<cmd_topic>/model/iris_with_standoffs/joint/rotor_3_joint/cmd_vel</cmd_topic>
<!-- <type>VELOCITY</type>
<p_gain>0.20</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>2.5</cmd_max>
<cmd_min>-2.5</cmd_min>
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim> -->
</control>
</plugin>
</model>
</sdf>
I created it based on the omnicopter model that I found on the web.
The video shows that the connection appears ( MulticopterMotorModel connection problem - Google Drive ), but the motors are not working, what could be the reason for this? And how to fix it?