mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
73 lines
3.4 KiB
XML
73 lines
3.4 KiB
XML
<?xml version="1.0" encoding="UTF-8"?>
|
|
<sdf version='1.9'>
|
|
<model name='x500'>
|
|
<include merge='true'>
|
|
<uri>model://x500-NoPlugin</uri>
|
|
</include>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<jointName>rotor_0_joint</jointName>
|
|
<linkName>rotor_0</linkName>
|
|
<turningDirection>ccw</turningDirection>
|
|
<timeConstantUp>0.0125</timeConstantUp>
|
|
<timeConstantDown>0.025</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>8.54858e-06</motorConstant>
|
|
<momentConstant>0.016</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>0</motorNumber>
|
|
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<jointName>rotor_1_joint</jointName>
|
|
<linkName>rotor_1</linkName>
|
|
<turningDirection>ccw</turningDirection>
|
|
<timeConstantUp>0.0125</timeConstantUp>
|
|
<timeConstantDown>0.025</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>8.54858e-06</motorConstant>
|
|
<momentConstant>0.016</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>1</motorNumber>
|
|
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<jointName>rotor_2_joint</jointName>
|
|
<linkName>rotor_2</linkName>
|
|
<turningDirection>cw</turningDirection>
|
|
<timeConstantUp>0.0125</timeConstantUp>
|
|
<timeConstantDown>0.025</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>8.54858e-06</motorConstant>
|
|
<momentConstant>0.016</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>2</motorNumber>
|
|
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<jointName>rotor_3_joint</jointName>
|
|
<linkName>rotor_3</linkName>
|
|
<turningDirection>cw</turningDirection>
|
|
<timeConstantUp>0.0125</timeConstantUp>
|
|
<timeConstantDown>0.025</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>8.54858e-06</motorConstant>
|
|
<momentConstant>0.016</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>3</motorNumber>
|
|
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
</model>
|
|
</sdf>
|