888 lines
24 KiB
Plaintext
888 lines
24 KiB
Plaintext
|
<?xml version="1.0" ?>
|
||
|
<sdf version="1.4">
|
||
|
<world name="default">
|
||
|
<gui>
|
||
|
<camera name="user_camera">
|
||
|
<pose>10 0 3 0 0 3.141592</pose>
|
||
|
</camera>
|
||
|
</gui>
|
||
|
<physics type="ode">
|
||
|
<gravity>0.0 0.0 -10.00</gravity>
|
||
|
<ode>
|
||
|
<solver>
|
||
|
<type>quick</type>
|
||
|
<iters>100</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>
|
||
|
<!--
|
||
|
<include>
|
||
|
<uri>model://drc_terrain</uri>
|
||
|
</include>
|
||
|
-->
|
||
|
|
||
|
<model name="ground_plane">
|
||
|
<static>true</static>
|
||
|
<link name="link">
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<plane>
|
||
|
<normal>0 0 1</normal>
|
||
|
<size>10000 10000</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>10000 10000</size>
|
||
|
</plane>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/WoodFloor</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">
|
||
|
<pose>5.0 0 1.5 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>-1.5 0.0 0.0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>5.8</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>10.8</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>10.8</izz>
|
||
|
</inertia>
|
||
|
<mass>200.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>10 1 1</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>0.3</mu>
|
||
|
<mu2>0.3</mu2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>10 1 1</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="camera" type="camera">
|
||
|
<pose>15 0 1.0 0 0.1 3.1416</pose>
|
||
|
<camera>
|
||
|
<horizontal_fov>1.347</horizontal_fov>
|
||
|
<image>
|
||
|
<width>320</width>
|
||
|
<height>240</height>
|
||
|
</image>
|
||
|
<clip>
|
||
|
<near>0.1</near>
|
||
|
<far>1000</far>
|
||
|
</clip>
|
||
|
</camera>
|
||
|
<always_on>1</always_on>
|
||
|
<update_rate>30</update_rate>
|
||
|
<visualize>true</visualize>
|
||
|
</sensor>
|
||
|
</link>
|
||
|
<link name="wheel_1">
|
||
|
<pose>9.0 0 0.25 1.57079 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.8</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.8</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.8</izz>
|
||
|
</inertia>
|
||
|
<mass>10.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.25</radius>
|
||
|
<length>0.03</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>0.3</mu>
|
||
|
<mu2>0.3</mu2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.25</radius>
|
||
|
<length>0.03</length>
|
||
|
</cylinder>
|
||
|
</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="wheel_2">
|
||
|
<pose>1.0 -2.0 0.25 1.57079 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.8</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.8</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.8</izz>
|
||
|
</inertia>
|
||
|
<mass>10.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.25</radius>
|
||
|
<length>0.03</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>0.3</mu>
|
||
|
<mu2>0.3</mu2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.25</radius>
|
||
|
<length>0.03</length>
|
||
|
</cylinder>
|
||
|
</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="wheel_3">
|
||
|
<pose>1.0 2.0 0.25 1.57079 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.8</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.8</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.8</izz>
|
||
|
</inertia>
|
||
|
<mass>10.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.25</radius>
|
||
|
<length>0.03</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>0.3</mu>
|
||
|
<mu2>0.3</mu2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.25</radius>
|
||
|
<length>0.03</length>
|
||
|
</cylinder>
|
||
|
</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_1">
|
||
|
<pose>-0.25 0 1.5 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0.0 0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0012</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.012</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.012</izz>
|
||
|
</inertia>
|
||
|
<mass>1.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.25 0.02 0.02</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.25 0.02 0.02</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.25 0 1.5 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0.5 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.01 1.0 0.2</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 0.5 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.01 1.0 0.2</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.25 0 1.5 0 0 3.141593</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0.5 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.01 1.0 0.2</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 0.5 0 0.0 0.0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.01 1.0 0.2</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="wheel_1_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wheel_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 1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>0.0001</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<joint name="wheel_2_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wheel_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 1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>0.0001</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<joint name="wheel_3_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wheel_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 1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>0.0001</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<joint name="rod_1_joint" type="revolute">
|
||
|
<parent>body</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>-1.0 0.0 0.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>
|
||
|
<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>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
|
||
|
|
||
|
|
||
|
|
||
|
<link name="wing_1">
|
||
|
<pose>3 0 1.5 0.3 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 5.5 0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.465</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.006</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.470</izz>
|
||
|
</inertia>
|
||
|
<mass>10.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<pose>0.0 5.5 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 10.0 0.01</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 5.5 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 10.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="wing_2">
|
||
|
<pose>3 0 1.5 -0.3 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 -5.5 0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.465</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.006</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.470</izz>
|
||
|
</inertia>
|
||
|
<mass>10.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<pose>0.0 -5.5 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 10.0 0.01</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 -5.5 0 0.0 0.0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 10.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="wing_1_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wing_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>0.0 1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>1.000000</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<joint name="wing_2_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wing_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>0.0 -1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>1.000000</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
|
||
|
|
||
|
<link name="wing_3">
|
||
|
<pose>9 0 1.5 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 2.0 0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0465</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.0006</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.0470</izz>
|
||
|
</inertia>
|
||
|
<mass>2.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<pose>0.0 2.0 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 3.0 0.01</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 2.0 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 3.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="wing_4">
|
||
|
<pose>9 0 1.5 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 -2.0 0 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0465</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.0006</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.0470</izz>
|
||
|
</inertia>
|
||
|
<mass>2.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<pose>0.0 -2.0 0 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 3.0 0.01</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 -2.0 0 0.0 0.0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0 3.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="wing_3_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wing_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>0.0 1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>1.000000</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<joint name="wing_4_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wing_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>0.0 -1.0 0.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>1.000000</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="wing_5_joint" type="revolute">
|
||
|
<parent>body</parent>
|
||
|
<child>wing_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>0.0 0.0 1.0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>1.000000</damping>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<cfm_damping>1</cfm_damping>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
|
||
|
<link name="wing_5">
|
||
|
<pose>9 0 2.0 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0.0 0 1 0.0 0.0 0.0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0465</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>0.0006</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>0.0470</izz>
|
||
|
</inertia>
|
||
|
<mass>2.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<pose>0.0 0 1 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.5 0.01 2.0</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<pose>0.0 0 1 0.0 0.0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.5 0.01 2.0</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>
|
||
|
|
||
|
<plugin name="gazebo_blade_1" filename="libLiftDragPlugin.so">
|
||
|
<a0>0.1</a0>
|
||
|
<cla>10.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</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>0 0 -1</forward>
|
||
|
<upward>-1 0 0</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>10.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</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>
|
||
|
<!-- link flipped about z-axis 180 degrees -->
|
||
|
<forward>0 0 1</forward>
|
||
|
<upward>1 0 0</upward>
|
||
|
<link_name>lift_drag_demo_model::blade_2</link_name>
|
||
|
</plugin>
|
||
|
<plugin name="gazebo_wing_1" filename="libLiftDragPlugin.so">
|
||
|
<a0>0.1</a0>
|
||
|
<cla>4.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</cda_stall>
|
||
|
<cma_stall>0.0</cma_stall>
|
||
|
<cp>0.0 5.0 0</cp>
|
||
|
<area>10</area>
|
||
|
<air_density>1.2041</air_density>
|
||
|
<forward>-1 0 0</forward>
|
||
|
<upward>0 0 1</upward>
|
||
|
<link_name>lift_drag_demo_model::wing_1</link_name>
|
||
|
</plugin>
|
||
|
<plugin name="gazebo_wing_2" filename="libLiftDragPlugin.so">
|
||
|
<a0>0.1</a0>
|
||
|
<cla>4.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</cda_stall>
|
||
|
<cma_stall>0.0</cma_stall>
|
||
|
<cp>0.0 -5.0 0</cp>
|
||
|
<area>10</area>
|
||
|
<air_density>1.2041</air_density>
|
||
|
<forward>-1 0 0</forward>
|
||
|
<upward>0 0 1</upward>
|
||
|
<link_name>lift_drag_demo_model::wing_2</link_name>
|
||
|
</plugin>
|
||
|
<plugin name="gazebo_wing_3" filename="libLiftDragPlugin.so">
|
||
|
<a0>0.02</a0>
|
||
|
<cla>4.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</cda_stall>
|
||
|
<cma_stall>0.0</cma_stall>
|
||
|
<cp>0.0 1.5 0</cp>
|
||
|
<area>3</area>
|
||
|
<air_density>1.2041</air_density>
|
||
|
<forward>-1 0 0</forward>
|
||
|
<upward>0 0 1</upward>
|
||
|
<link_name>lift_drag_demo_model::wing_3</link_name>
|
||
|
</plugin>
|
||
|
<plugin name="gazebo_wing_4" filename="libLiftDragPlugin.so">
|
||
|
<a0>0.02</a0>
|
||
|
<cla>4.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</cda_stall>
|
||
|
<cma_stall>0.0</cma_stall>
|
||
|
<cp>0.0 -1.5 0</cp>
|
||
|
<area>3</area>
|
||
|
<air_density>1.2041</air_density>
|
||
|
<forward>-1 0 0</forward>
|
||
|
<upward>0 0 1</upward>
|
||
|
<link_name>lift_drag_demo_model::wing_4</link_name>
|
||
|
</plugin>
|
||
|
<plugin name="gazebo_wing_5" filename="libLiftDragPlugin.so">
|
||
|
<!-- force turn -->
|
||
|
<a0>0.0</a0>
|
||
|
<cla>8.000</cla>
|
||
|
<cda>0.001</cda>
|
||
|
<cma>0.00</cma>
|
||
|
<alpha_stall>10.0</alpha_stall>
|
||
|
<cla_stall>0.0</cla_stall>
|
||
|
<cda_stall>0.01</cda_stall>
|
||
|
<cma_stall>0.0</cma_stall>
|
||
|
<cp>0.0 0 1.0</cp>
|
||
|
<area>3</area>
|
||
|
<air_density>1.2041</air_density>
|
||
|
<forward>-1 0 0</forward>
|
||
|
<upward>0 -1 0</upward>
|
||
|
<link_name>lift_drag_demo_model::wing_5</link_name>
|
||
|
</plugin>
|
||
|
|
||
|
</model>
|
||
|
</world>
|
||
|
</sdf>
|