mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-30 00:44:07 +08:00
517 lines
15 KiB
XML
517 lines
15 KiB
XML
<?xml version="1.0" encoding="UTF-8"?>
|
|
<sdf version='1.9'>
|
|
<model name='x500-NoPlugin'>
|
|
<pose>0 0 .24 0 0 0</pose>
|
|
<self_collide>false</self_collide>
|
|
<static>false</static>
|
|
<link name="base_link">
|
|
<inertial>
|
|
<mass>2.0</mass>
|
|
<inertia>
|
|
<ixx>0.02166666666666667</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>0.02166666666666667</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>0.04000000000000001</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<gravity>true</gravity>
|
|
<velocity_decay/>
|
|
<visual name="base_link_visual">
|
|
<pose>0 0 .025 0 0 3.141592654</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/NXP-HGD-CF.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="5010_motor_base_0">
|
|
<pose>0.174 0.174 .032 0 0 -.45</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="5010_motor_base_1">
|
|
<pose>-0.174 0.174 .032 0 0 -.45</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="5010_motor_base_2">
|
|
<pose>0.174 -0.174 .032 0 0 -.45</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="5010_motor_base_3">
|
|
<pose>-0.174 -0.174 .032 0 0 -.45</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="NXP_FMUK66_FRONT">
|
|
<pose>0.047 .001 .043 1 0 1.57</pose>
|
|
<cast_shadows>false</cast_shadows>
|
|
<geometry>
|
|
<plane>
|
|
<normal>0 0 1</normal>
|
|
<size>.013 .007</size>
|
|
</plane>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>1.0 1.0 1.0</diffuse>
|
|
<specular>1.0 1.0 1.0</specular>
|
|
<pbr>
|
|
<metal>
|
|
<albedo_map>model://x500-NoPlugin/materials/textures/nxp.png</albedo_map>
|
|
</metal>
|
|
</pbr>
|
|
</material>
|
|
</visual>
|
|
<visual name="NXP_FMUK66_TOP">
|
|
<pose>-0.023 0 .0515 0 0 -1.57</pose>
|
|
<cast_shadows>false</cast_shadows>
|
|
<geometry>
|
|
<plane>
|
|
<normal>0 0 1</normal>
|
|
<size>.013 .007</size>
|
|
</plane>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>1.0 1.0 1.0</diffuse>
|
|
<specular>1.0 1.0 1.0</specular>
|
|
<pbr>
|
|
<metal>
|
|
<albedo_map>model://x500-NoPlugin/materials/textures/nxp.png</albedo_map>
|
|
</metal>
|
|
</pbr>
|
|
</material>
|
|
</visual>
|
|
<visual name="RDDRONE_FMUK66_TOP">
|
|
<pose>-.03 0 .0515 0 0 -1.57</pose>
|
|
<cast_shadows>false</cast_shadows>
|
|
<geometry>
|
|
<plane>
|
|
<normal>0 0 1</normal>
|
|
<size>.032 .0034</size>
|
|
</plane>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>1.0 1.0 1.0</diffuse>
|
|
<specular>1.0 1.0 1.0</specular>
|
|
<pbr>
|
|
<metal>
|
|
<albedo_map>model://x500-NoPlugin/materials/textures/rd.png</albedo_map>
|
|
</metal>
|
|
</pbr>
|
|
</material>
|
|
</visual>
|
|
<collision name="base_link_collision_0">
|
|
<pose>0 0 .007 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.35355339059327373 0.35355339059327373 0.05</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<collision name="base_link_collision_1">
|
|
<pose>0 -0.098 -.123 -0.35 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.015 0.015 0.21</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<collision name="base_link_collision_2">
|
|
<pose>0 0.098 -.123 0.35 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.015 0.015 0.21</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<collision name="base_link_collision_3">
|
|
<pose>0 -0.132 -.2195 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.25 0.015 0.015</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<collision name="base_link_collision_4">
|
|
<pose>0 0.132 -.2195 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.25 0.015 0.015</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<sensor name="imu_sensor" type="imu">
|
|
<always_on>1</always_on>
|
|
<update_rate>250</update_rate>
|
|
</sensor>
|
|
</link>
|
|
<link name="rotor_0">
|
|
<gravity>true</gravity>
|
|
<self_collide>false</self_collide>
|
|
<velocity_decay/>
|
|
<pose>0.174 -0.174 0.06 0 0 0</pose>
|
|
<inertial>
|
|
<mass>0.016076923076923075</mass>
|
|
<inertia>
|
|
<ixx>3.8464910483993325e-07</ixx>
|
|
<iyy>2.6115851691700804e-05</iyy>
|
|
<izz>2.649858234714004e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name="rotor_0_visual">
|
|
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
|
|
<uri>model://x500-NoPlugin/meshes/1345_prop_ccw.stl</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/DarkGrey</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<visual name="rotor_0_visual_motor_bell">
|
|
<pose>0 0 -.032 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<collision name="rotor_0_collision">
|
|
<pose>0 0 0 0 0 0 </pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
</link>
|
|
<joint name="rotor_0_joint" type="revolute">
|
|
<parent>base_link</parent>
|
|
<child>rotor_0</child>
|
|
<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">
|
|
<gravity>true</gravity>
|
|
<self_collide>false</self_collide>
|
|
<velocity_decay/>
|
|
<pose>-0.174 0.174 0.06 0 0 0</pose>
|
|
<inertial>
|
|
<mass>0.016076923076923075</mass>
|
|
<inertia>
|
|
<ixx>3.8464910483993325e-07</ixx>
|
|
<iyy>2.6115851691700804e-05</iyy>
|
|
<izz>2.649858234714004e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name="rotor_1_visual">
|
|
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
|
|
<uri>model://x500-NoPlugin/meshes/1345_prop_ccw.stl</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/DarkGrey</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<visual name="rotor_1_visual_motor_top">
|
|
<pose>0 0 -.032 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<collision name="rotor_1_collision">
|
|
<pose>0 0 0 0 0 0 </pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
</link>
|
|
<joint name="rotor_1_joint" type="revolute">
|
|
<parent>base_link</parent>
|
|
<child>rotor_1</child>
|
|
<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">
|
|
<gravity>true</gravity>
|
|
<self_collide>false</self_collide>
|
|
<velocity_decay/>
|
|
<pose>0.174 0.174 0.06 0 0 0</pose>
|
|
<inertial>
|
|
<mass>0.016076923076923075</mass>
|
|
<inertia>
|
|
<ixx>3.8464910483993325e-07</ixx>
|
|
<iyy>2.6115851691700804e-05</iyy>
|
|
<izz>2.649858234714004e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name="rotor_2_visual">
|
|
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
|
|
<uri>model://x500-NoPlugin/meshes/1345_prop_cw.stl</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/DarkGrey</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<visual name="rotor_2_visual_motor_top">
|
|
<pose>0 0 -.032 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<collision name="rotor_2_collision">
|
|
<pose>0 0 0 0 0 0 </pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
</link>
|
|
<joint name="rotor_2_joint" type="revolute">
|
|
<parent>base_link</parent>
|
|
<child>rotor_2</child>
|
|
<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">
|
|
<gravity>true</gravity>
|
|
<self_collide>false</self_collide>
|
|
<velocity_decay/>
|
|
<pose>-0.174 -0.174 0.06 0 0 0</pose>
|
|
<inertial>
|
|
<mass>0.016076923076923075</mass>
|
|
<inertia>
|
|
<ixx>3.8464910483993325e-07</ixx>
|
|
<iyy>2.6115851691700804e-05</iyy>
|
|
<izz>2.649858234714004e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name="rotor_3_visual">
|
|
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
|
|
<uri>model://x500-NoPlugin/meshes/1345_prop_cw.stl</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/DarkGrey</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<visual name="rotor_3_visual_motor_top">
|
|
<pose>0 0 -.032 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<collision name="rotor_3_collision">
|
|
<pose>0 0 0 0 0 0 </pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
|
|
</box>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<min_depth>0.001</min_depth>
|
|
<max_vel>0</max_vel>
|
|
</ode>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
</link>
|
|
<joint name="rotor_3_joint" type="revolute">
|
|
<parent>base_link</parent>
|
|
<child>rotor_3</child>
|
|
<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>
|
|
</model>
|
|
</sdf>
|