mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
- much simpler direct interface using Ignition Transport - in tree models and worlds - control allocation output configuration, no more magic actuator mapping to mavlink and back - currently requires no custom Gazebo plugins (keeping things as lightweight and simple as possible) Co-authored-by: Jaeyoung-Lim <jalim@ethz.ch>
372 lines
13 KiB
XML
372 lines
13 KiB
XML
<?xml version="1.0" encoding="UTF-8"?>
|
|
<sdf version="1.6">
|
|
<model name="x3">
|
|
<pose>0 0 0.053302 0 0 0</pose>
|
|
<link name="base_link">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<inertial>
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<mass>1.5</mass>
|
|
<inertia>
|
|
<ixx>0.0347563</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>0.07</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>0.0977</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="base_link_inertia_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.47 0.47 0.11</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="base_link_inertia_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>meshes/x3.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<sensor name="imu_sensor" type="imu">
|
|
<always_on>1</always_on>
|
|
<update_rate>250</update_rate>
|
|
</sensor>
|
|
</link>
|
|
<link name="rotor_0">
|
|
<pose frame="">0.13 -0.22 0.023 0 -0 0</pose>
|
|
<inertial>
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<mass>0.005</mass>
|
|
<inertia>
|
|
<ixx>9.75e-07</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>4.17041e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>4.26041e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="rotor_0_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.005</length>
|
|
<radius>0.1</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode />
|
|
</contact>
|
|
<friction>
|
|
<ode />
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="rotor_0_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.1 0.1 0.1</scale>
|
|
<uri>meshes/propeller_ccw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay />
|
|
</link>
|
|
<joint name="rotor_0_joint" type="revolute">
|
|
<child>rotor_0</child>
|
|
<parent>base_link</parent>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
<use_parent_model_frame>1</use_parent_model_frame>
|
|
</axis>
|
|
</joint>
|
|
<link name="rotor_1">
|
|
<pose frame="">-0.13 0.2 0.023 0 -0 0</pose>
|
|
<inertial>
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<mass>0.005</mass>
|
|
<inertia>
|
|
<ixx>9.75e-07</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>4.17041e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>4.26041e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="rotor_1_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.005</length>
|
|
<radius>0.1</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode />
|
|
</contact>
|
|
<friction>
|
|
<ode />
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="rotor_1_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.1 0.1 0.1</scale>
|
|
<uri>meshes/propeller_ccw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Red</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay />
|
|
</link>
|
|
<joint name="rotor_1_joint" type="revolute">
|
|
<child>rotor_1</child>
|
|
<parent>base_link</parent>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
<use_parent_model_frame>1</use_parent_model_frame>
|
|
</axis>
|
|
</joint>
|
|
<link name="rotor_2">
|
|
<pose frame="">0.13 0.22 0.023 0 -0 0</pose>
|
|
<inertial>
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<mass>0.005</mass>
|
|
<inertia>
|
|
<ixx>9.75e-07</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>4.17041e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>4.26041e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="rotor_2_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.005</length>
|
|
<radius>0.1</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode />
|
|
</contact>
|
|
<friction>
|
|
<ode />
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="rotor_2_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.1 0.1 0.1</scale>
|
|
<uri>meshes/propeller_cw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay />
|
|
</link>
|
|
<joint name="rotor_2_joint" type="revolute">
|
|
<child>rotor_2</child>
|
|
<parent>base_link</parent>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
<use_parent_model_frame>1</use_parent_model_frame>
|
|
</axis>
|
|
</joint>
|
|
<link name="rotor_3">
|
|
<pose frame="">-0.13 -0.2 0.023 0 -0 0</pose>
|
|
<inertial>
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<mass>0.005</mass>
|
|
<inertia>
|
|
<ixx>9.75e-07</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>4.17041e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>4.26041e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="rotor_3_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.005</length>
|
|
<radius>0.1</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode />
|
|
</contact>
|
|
<friction>
|
|
<ode />
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="rotor_3_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.1 0.1 0.1</scale>
|
|
<uri>meshes/propeller_cw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Red</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay />
|
|
</link>
|
|
<joint name="rotor_3_joint" type="revolute">
|
|
<child>rotor_3</child>
|
|
<parent>base_link</parent>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<spring_reference>0</spring_reference>
|
|
<spring_stiffness>0</spring_stiffness>
|
|
</dynamics>
|
|
<use_parent_model_frame>1</use_parent_model_frame>
|
|
</axis>
|
|
</joint>
|
|
<plugin filename="libignition-gazebo-imu-system.so" name="ignition::gazebo::systems::Imu" />
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<robotNamespace>x3</robotNamespace>
|
|
<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">
|
|
<robotNamespace>x3</robotNamespace>
|
|
<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">
|
|
<robotNamespace>x3</robotNamespace>
|
|
<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">
|
|
<robotNamespace>x3</robotNamespace>
|
|
<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>
|