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>
823 lines
30 KiB
XML
823 lines
30 KiB
XML
<?xml version="1.0" encoding="UTF-8"?>
|
|
<sdf version="1.6">
|
|
<model name="x4">
|
|
<pose>0 0 0.121078 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>3.42</mass>
|
|
<inertia>
|
|
<ixx>0.075</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>0.075</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>0.148916</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="base_link_inertia_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.3 0.3 0.25</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/x4.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="marker_visual_1">
|
|
<pose frame="">-0.1 0 0.077 0 -0.1 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>meshes/led.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="marker_visual_2">
|
|
<pose frame="">-0.09 0.059 0.059 -0.785397 -0 0.2</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>meshes/led.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="marker_visual_3">
|
|
<pose frame="">-0.09 -0.059 0.059 0.785397 -0 -0.2</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>meshes/led.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="downward_flashlight_visual">
|
|
<pose frame="">-0.043704 0 0.102914 -0.2 0.000158 -1.57002</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.01 0.01 0.01</scale>
|
|
<uri>meshes/spotlight.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="left_flashlight_visual">
|
|
<pose frame="">-0.071985 0.090826 0.066102 0.06 -4.8e-05 -1.27</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.01 0.01 0.01</scale>
|
|
<uri>meshes/spotlight.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="right_flashlight_visual">
|
|
<pose frame="">-0.071985 -0.090826 0.066102 0.06 -4.8e-05 -1.87</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.01 0.01 0.01</scale>
|
|
<uri>meshes/spotlight.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<light name="right_light_source" type="spot">
|
|
<pose frame="">-0.0 -0.11 0.07 3.131592653589795 -1.5107899999999999 2.841592653589791</pose>
|
|
<attenuation>
|
|
<range>15</range>
|
|
<linear>0</linear>
|
|
<constant>0.1</constant>
|
|
<quadratic>0.01</quadratic>
|
|
</attenuation>
|
|
<diffuse>0.8 0.8 0.5 1</diffuse>
|
|
<specular>0.8 0.8 0.5 1</specular>
|
|
<spot>
|
|
<inner_angle>1</inner_angle>
|
|
<outer_angle>1.1</outer_angle>
|
|
<falloff>1</falloff>
|
|
</spot>
|
|
<direction>0 0 -1</direction>
|
|
<cast_shadows>1</cast_shadows>
|
|
</light>
|
|
<light name="downward_flashlight_source" type="spot">
|
|
<pose frame="">0.03 0 0.09 -0.01 -1.3708026535897933 0</pose>
|
|
<attenuation>
|
|
<range>15</range>
|
|
<linear>0</linear>
|
|
<constant>0.1</constant>
|
|
<quadratic>0.01</quadratic>
|
|
</attenuation>
|
|
<diffuse>0.8 0.8 0.5 1</diffuse>
|
|
<specular>0.8 0.8 0.5 1</specular>
|
|
<spot>
|
|
<inner_angle>1</inner_angle>
|
|
<outer_angle>1.1</outer_angle>
|
|
<falloff>1</falloff>
|
|
</spot>
|
|
<direction>0 0 -1</direction>
|
|
<cast_shadows>1</cast_shadows>
|
|
</light>
|
|
<light name="left_flashlight_source" type="spot">
|
|
<pose frame="">-0.0 0.11 0.07 3.131592653589795 -1.5107899999999999 -2.841592653589791</pose>
|
|
<attenuation>
|
|
<range>15</range>
|
|
<linear>0</linear>
|
|
<constant>0.1</constant>
|
|
<quadratic>0.01</quadratic>
|
|
</attenuation>
|
|
<diffuse>0.8 0.8 0.5 1</diffuse>
|
|
<specular>0.8 0.8 0.5 1</specular>
|
|
<spot>
|
|
<inner_angle>1</inner_angle>
|
|
<outer_angle>1.1</outer_angle>
|
|
<falloff>1</falloff>
|
|
</spot>
|
|
<direction>0 0 -1</direction>
|
|
<cast_shadows>1</cast_shadows>
|
|
</light>
|
|
<sensor name="imu_sensor" type="imu">
|
|
<always_on>1</always_on>
|
|
<update_rate>250</update_rate>
|
|
<imu>
|
|
<angular_velocity>
|
|
<x>
|
|
<noise type="gaussian">
|
|
<mean>0</mean>
|
|
<stddev>0.009</stddev>
|
|
<bias_mean>0.00075</bias_mean>
|
|
<bias_stddev>0.005</bias_stddev>
|
|
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
|
|
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
|
|
<precision>0.00025</precision>
|
|
</noise>
|
|
</x>
|
|
<y>
|
|
<noise type="gaussian">
|
|
<mean>0</mean>
|
|
<stddev>0.009</stddev>
|
|
<bias_mean>0.00075</bias_mean>
|
|
<bias_stddev>0.005</bias_stddev>
|
|
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
|
|
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
|
|
<precision>0.00025</precision>
|
|
</noise>
|
|
</y>
|
|
<z>
|
|
<noise type="gaussian">
|
|
<mean>0</mean>
|
|
<stddev>0.009</stddev>
|
|
<bias_mean>0.00075</bias_mean>
|
|
<bias_stddev>0.005</bias_stddev>
|
|
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
|
|
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
|
|
<precision>0.00025</precision>
|
|
</noise>
|
|
</z>
|
|
</angular_velocity>
|
|
<linear_acceleration>
|
|
<x>
|
|
<noise type="gaussian">
|
|
<mean>0</mean>
|
|
<stddev>0.021</stddev>
|
|
<bias_mean>0.05</bias_mean>
|
|
<bias_stddev>0.0075</bias_stddev>
|
|
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
|
|
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
|
|
<precision>0.005</precision>
|
|
</noise>
|
|
</x>
|
|
<y>
|
|
<noise type="gaussian">
|
|
<mean>0</mean>
|
|
<stddev>0.021</stddev>
|
|
<bias_mean>0.05</bias_mean>
|
|
<bias_stddev>0.0075</bias_stddev>
|
|
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
|
|
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
|
|
<precision>0.005</precision>
|
|
</noise>
|
|
</y>
|
|
<z>
|
|
<noise type="gaussian">
|
|
<mean>0</mean>
|
|
<stddev>0.021</stddev>
|
|
<bias_mean>0.05</bias_mean>
|
|
<bias_stddev>0.0075</bias_stddev>
|
|
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
|
|
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
|
|
<precision>0.005</precision>
|
|
</noise>
|
|
</z>
|
|
</linear_acceleration>
|
|
</imu>
|
|
</sensor>
|
|
|
|
<visual name="camera_mount_base_visual">
|
|
<pose>0.05 0 -0.030 0 0.0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.06 0.06 0.006</size>
|
|
</box>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="camera_mount_arm_visual">
|
|
<pose>0.08 0 -0.040 0 0.0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.005</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="camera_mount_arm2_visual">
|
|
<pose>0.08 0 -0.08 0 1.57 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.01</radius>
|
|
<length>0.025</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="camera_visual">
|
|
<pose>0.1 0 -0.08 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.02 0.025 0.025</size>
|
|
</box>
|
|
</geometry>
|
|
</visual>
|
|
<sensor name="camera_front" type="rgbd_camera">
|
|
<pose>0.2 0 0 0 +.785 0</pose>
|
|
<always_on>1</always_on>
|
|
<update_rate>20</update_rate>
|
|
<camera name="camera_front">
|
|
<horizontal_fov>1.0472</horizontal_fov>
|
|
<lens>
|
|
<intrinsics>
|
|
<!-- fx = fy = width / ( 2 * tan (hfov / 2 ) ) -->
|
|
<fx>277.1</fx>
|
|
<fy>277.1</fy>
|
|
<!-- cx = ( width + 1 ) / 2 -->
|
|
<cx>160.5</cx>
|
|
<!-- cy = ( height + 1 ) / 2 -->
|
|
<cy>120.5</cy>
|
|
<s>0</s>
|
|
</intrinsics>
|
|
</lens>
|
|
<distortion>
|
|
<k1>0.0</k1>
|
|
<k2>0.0</k2>
|
|
<k3>0.0</k3>
|
|
<p1>0.0</p1>
|
|
<p2>0.0</p2>
|
|
<center>0.5 0.5</center>
|
|
</distortion>
|
|
<image>
|
|
<width>320</width>
|
|
<height>240</height>
|
|
<format>R8G8B8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.01</near>
|
|
<far>300</far>
|
|
</clip>
|
|
<depth_camera>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>10</far>
|
|
</clip>
|
|
</depth_camera>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
</sensor>
|
|
</link>
|
|
<link name="rotor_0">
|
|
<pose frame="">0.247 0.1506 0.028 0.087267 0 0.523599</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>8.13545e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.22545e-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.1397</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>1 1 1</scale>
|
|
<uri>meshes/neo11_propeller_ccw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>1 0 0 1</diffuse>
|
|
<script>
|
|
<name>Gazebo/Red</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
<cast_shadows>0</cast_shadows>
|
|
</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.043578 -0.075479 0.996195</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.00067 0.28929 0.028 0 -0.087267 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>8.13545e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.22545e-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.1397</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>1 1 1</scale>
|
|
<uri>meshes/neo11_propeller_cw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0 0 1 1</diffuse>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
<cast_shadows>0</cast_shadows>
|
|
</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.087156 0 0.996195</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.2501 0.1454 0.028 0.087267 -0 2.61799</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>8.13545e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.22545e-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.1397</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>1 1 1</scale>
|
|
<uri>meshes/neo11_propeller_ccw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0 0 1 1</diffuse>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
<cast_shadows>0</cast_shadows>
|
|
</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.043578 0.075479 0.996195</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.2501 -0.1454 0.028 -0.087267 -0 -2.61799</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>8.13545e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.22545e-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.1397</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>1 1 1</scale>
|
|
<uri>meshes/neo11_propeller_cw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0 0 1 1</diffuse>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
<cast_shadows>0</cast_shadows>
|
|
</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.043578 -0.075479 0.996195</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_4">
|
|
<pose frame="">-0.00067 -0.28929 0.028 -0 0.087267 -3.14159</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>8.13545e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.22545e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="rotor_4_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.005</length>
|
|
<radius>0.1397</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode />
|
|
</contact>
|
|
<friction>
|
|
<ode />
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="rotor_4_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>meshes/neo11_propeller_ccw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>0 0 1 1</diffuse>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
<cast_shadows>0</cast_shadows>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay />
|
|
</link>
|
|
<joint name="rotor_4_joint" type="revolute">
|
|
<child>rotor_4</child>
|
|
<parent>base_link</parent>
|
|
<axis>
|
|
<xyz>-0.087156 -0 0.996195</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_5">
|
|
<pose frame="">0.247 -0.1506 0.028 -0.087267 0 -0.523599</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>8.13545e-05</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.22545e-05</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="rotor_5_collision">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.005</length>
|
|
<radius>0.1397</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode />
|
|
</contact>
|
|
<friction>
|
|
<ode />
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="rotor_5_visual">
|
|
<pose frame="">0 0 0 0 -0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>1 1 1</scale>
|
|
<uri>meshes/neo11_propeller_cw.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>1 0 0 1</diffuse>
|
|
<script>
|
|
<name>Gazebo/Red</name>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
</script>
|
|
</material>
|
|
<cast_shadows>0</cast_shadows>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay />
|
|
</link>
|
|
<joint name="rotor_5_joint" type="revolute">
|
|
<child>rotor_5</child>
|
|
<parent>base_link</parent>
|
|
<axis>
|
|
<xyz>0.043578 0.075479 0.996195</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>x4</robotNamespace>
|
|
<jointName>rotor_0_joint</jointName>
|
|
<linkName>rotor_0</linkName>
|
|
<turningDirection>ccw</turningDirection>
|
|
<timeConstantUp>0.0182</timeConstantUp>
|
|
<timeConstantDown>0.0182</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>1.269e-05</motorConstant>
|
|
<momentConstant>0.016754</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>0</motorNumber>
|
|
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
|
|
<rotorDragCoefficient>0</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>0</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>2</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<robotNamespace>x4</robotNamespace>
|
|
<jointName>rotor_1_joint</jointName>
|
|
<linkName>rotor_1</linkName>
|
|
<turningDirection>cw</turningDirection>
|
|
<timeConstantUp>0.0182</timeConstantUp>
|
|
<timeConstantDown>0.0182</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>1.269e-05</motorConstant>
|
|
<momentConstant>0.016754</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>1</motorNumber>
|
|
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
|
|
<rotorDragCoefficient>0</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>0</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>2</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<robotNamespace>x4</robotNamespace>
|
|
<jointName>rotor_2_joint</jointName>
|
|
<linkName>rotor_2</linkName>
|
|
<turningDirection>ccw</turningDirection>
|
|
<timeConstantUp>0.0182</timeConstantUp>
|
|
<timeConstantDown>0.0182</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>1.269e-05</motorConstant>
|
|
<momentConstant>0.016754</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>2</motorNumber>
|
|
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
|
|
<rotorDragCoefficient>0</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>0</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>2</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<robotNamespace>x4</robotNamespace>
|
|
<jointName>rotor_3_joint</jointName>
|
|
<linkName>rotor_3</linkName>
|
|
<turningDirection>cw</turningDirection>
|
|
<timeConstantUp>0.0182</timeConstantUp>
|
|
<timeConstantDown>0.0182</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>1.269e-05</motorConstant>
|
|
<momentConstant>0.016754</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>3</motorNumber>
|
|
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
|
|
<rotorDragCoefficient>0</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>0</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>2</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<robotNamespace>x4</robotNamespace>
|
|
<jointName>rotor_4_joint</jointName>
|
|
<linkName>rotor_4</linkName>
|
|
<turningDirection>ccw</turningDirection>
|
|
<timeConstantUp>0.0182</timeConstantUp>
|
|
<timeConstantDown>0.0182</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>1.269e-05</motorConstant>
|
|
<momentConstant>0.016754</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>4</motorNumber>
|
|
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
|
|
<rotorDragCoefficient>0</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>0</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>2</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
|
<robotNamespace>x4</robotNamespace>
|
|
<jointName>rotor_5_joint</jointName>
|
|
<linkName>rotor_5</linkName>
|
|
<turningDirection>cw</turningDirection>
|
|
<timeConstantUp>0.0182</timeConstantUp>
|
|
<timeConstantDown>0.0182</timeConstantDown>
|
|
<maxRotVelocity>1000.0</maxRotVelocity>
|
|
<motorConstant>1.269e-05</motorConstant>
|
|
<momentConstant>0.016754</momentConstant>
|
|
<commandSubTopic>command/motor_speed</commandSubTopic>
|
|
<motorNumber>5</motorNumber>
|
|
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
|
|
<rotorDragCoefficient>0</rotorDragCoefficient>
|
|
<rollingMomentCoefficient>0</rollingMomentCoefficient>
|
|
<rotorVelocitySlowdownSim>2</rotorVelocitySlowdownSim>
|
|
<motorType>velocity</motorType>
|
|
</plugin>
|
|
|
|
<plugin filename="ignition-gazebo-odometry-publisher-system" name="ignition::gazebo::systems::OdometryPublisher">
|
|
<dimensions>3</dimensions>
|
|
<odom_frame>x4/odom</odom_frame>
|
|
<robot_base_frame>x4/base_footprint</robot_base_frame>
|
|
</plugin>
|
|
</model>
|
|
</sdf>
|