ppovb5fc7/gazebo/worlds/quad_rotor_demo_2.world

1077 lines
30 KiB
Plaintext
Raw Normal View History

2019-03-04 17:11:56 +08:00
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<physics type="ode">
<gravity>0.0 0.0 -10.0</gravity>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>0.8</sor>
</solver>
<constraints>
<cfm>0.0</cfm>
<erp>0.2</erp>
<contact_max_correcting_vel>0.1</contact_max_correcting_vel>
<contact_surface_layer>0.0</contact_surface_layer>
</constraints>
</ode>
<real_time_update_rate>0</real_time_update_rate>
<max_step_size>0.001</max_step_size>
</physics>
<include>
<uri>model://sun</uri>
</include>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1000 1000</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1000 1000</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
<model name="lift_drag_demo_model">
<pose>0 0 0 0 0 0</pose>
<static>false</static>
<link name="body_1">
<pose>1.75 0 0.1 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1.8</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>10.8</iyy>
<iyz>0.0</iyz>
<izz>10.8</izz>
</inertia>
<mass>10.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>3.6 0.2 0.2</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.1</mu>
<mu2>0.1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size>3.6 0.2 0.2</size>
</box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
<sensor name='imu_sensor' type='imu'>
<always_on>1</always_on>
<update_rate>1000</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0002</stddev>
<bias_mean>7.5e-06</bias_mean>
<bias_stddev>8e-07</bias_stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.017</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</z>
</linear_acceleration>
</imu>
<pose>0 0 0 0 0 0</pose>
</sensor>
</link>
<link name="rod_1">
<pose>0 0 0.24 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.012</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.012</iyy>
<iyz>0.0</iyz>
<izz>0.0012</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_1">
<pose>0 0 0.28 0 0 0</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.5 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_2">
<pose>0 0 0.28 0 0 3.141593</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.2 0.5 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<joint name="rod_1_joint" type="revolute">
<parent>body_1</parent>
<child>rod_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
</limit>
<xyz>0.0 0.0 -1.0</xyz>
<dynamics>
<damping>0.0001</damping>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_1_joint" type="revolute">
<parent>rod_1</parent>
<child>blade_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_2_joint" type="revolute">
<parent>rod_1</parent>
<child>blade_2</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>-1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<link name="rod_2">
<pose>3.5 0 0.24 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.012</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.012</iyy>
<iyz>0.0</iyz>
<izz>0.0012</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_3">
<pose>3.5 0 0.28 0 0 0</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.5 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_4">
<pose>3.5 0 0.28 0 0 3.141593</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.2 0.5 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<joint name="rod_2_joint" type="revolute">
<parent>body_1</parent>
<child>rod_2</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
<dynamics>
<damping>0.0001</damping>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_3_joint" type="revolute">
<parent>rod_2</parent>
<child>blade_3</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_4_joint" type="revolute">
<parent>rod_2</parent>
<child>blade_4</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<!-- -->
<joint name="gear_joint_1" type="gearbox">
<parent>rod_1</parent>
<child>rod_2</child>
<gearbox_ratio>1.0</gearbox_ratio>
<gearbox_reference_body>body_1</gearbox_reference_body>
<axis>
<xyz>0.000000 0.000000 1.000000</xyz>
</axis>
<axis2>
<xyz>0.000000 0.000000 1.000000</xyz>
</axis2>
</joint>
<plugin name="gazebo_blade_1" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_1</link_name>
</plugin>
<plugin name="gazebo_blade_2" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_2</link_name>
</plugin>
<plugin name="gazebo_blade_3" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>-1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_3</link_name>
</plugin>
<plugin name="gazebo_blade_4" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>-1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_4</link_name>
</plugin>
<link name="body_2">
<pose>1.75 0 0.1 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>10.8</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1.8</iyy>
<iyz>0.0</iyz>
<izz>10.8</izz>
</inertia>
<mass>10.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.2 3.6 0.2</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.1</mu>
<mu2>0.1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 3.6 0.2</size>
</box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="rod_3">
<pose>1.75 -1.75 0.24 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.012</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.012</iyy>
<iyz>0.0</iyz>
<izz>0.0012</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_5">
<pose>1.75 -1.75 0.28 0 0 0</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.5 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_6">
<pose>1.75 -1.75 0.28 0 0 3.141593</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.2 0.5 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<joint name="rod_3_joint" type="revolute">
<parent>body_2</parent>
<child>rod_3</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
<dynamics>
<damping>0.0001</damping>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_5_joint" type="revolute">
<parent>rod_3</parent>
<child>blade_5</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_6_joint" type="revolute">
<parent>rod_3</parent>
<child>blade_6</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>-1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<link name="rod_4">
<pose>1.75 1.75 0.24 0 0 0</pose>
<inertial>
<pose>0.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.012</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.012</iyy>
<iyz>0.0</iyz>
<izz>0.0012</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.02 0.02 0.08</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_7">
<pose>1.75 1.75 0.28 0 0 0</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.5 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<link name="blade_8">
<pose>1.75 1.75 0.28 0 0 3.141593</pose>
<inertial>
<pose>0.0 0.25 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0000465</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0000006</iyy>
<iyz>0.0</iyz>
<izz>0.0000470</izz>
</inertia>
<mass>0.01</mass>
</inertial>
<collision name="collision">
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0.5 0 0.0 0.0 0</pose>
<geometry>
<box>
<size>0.2 1.0 0.01</size>
</box>
</geometry>
<material>
<ambient>0.2 0.5 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
</link>
<joint name="body_joint" type="revolute">
<parent>body_1</parent>
<child>body_2</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
<dynamics>
<damping>0.0001</damping>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="rod_4_joint" type="revolute">
<parent>body_2</parent>
<child>rod_4</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
<dynamics>
<damping>0.0001</damping>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_7_joint" type="revolute">
<parent>rod_4</parent>
<child>blade_7</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<joint name="blade_8_joint" type="revolute">
<parent>rod_4</parent>
<child>blade_8</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-0.0</lower>
<upper>0.0</upper>
</limit>
<xyz>-1.0 0.0 0.0</xyz>
<dynamics>
<damping>1.000000</damping>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.004</cfm>
<erp>0.2</erp>
</limit>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<!-- -->
<joint name="gear_joint_2" type="gearbox">
<parent>rod_3</parent>
<child>rod_4</child>
<gearbox_ratio>-1.0</gearbox_ratio>
<gearbox_reference_body>body_2</gearbox_reference_body>
<axis>
<xyz>0.000000 0.000000 1.000000</xyz>
</axis>
<axis2>
<xyz>0.000000 0.000000 1.000000</xyz>
</axis2>
</joint>
<plugin name="gazebo_blade_5" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>-1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_5</link_name>
</plugin>
<plugin name="gazebo_blade_6" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>-1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_6</link_name>
</plugin>
<plugin name="gazebo_blade_7" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>-1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_7</link_name>
</plugin>
<plugin name="gazebo_blade_8" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>0.100</cla>
<cda>0.01</cda>
<cma>0.00</cma>
<alpha_stall>0.2</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</cda_stall>
<cma_stall>0.0</cma_stall>
<cp>0.0 0.5 0</cp>
<area>0.2</area>
<air_density>1.2041</air_density>
<forward>-1 0 0</forward>
<upward>0 0 1</upward>
<link_name>lift_drag_demo_model::blade_8</link_name>
</plugin>
</model>
</world>
</sdf>