ppovb5fc7/gazebo/test/worlds/lift_drag_plugin.world

273 lines
7.2 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<physics type="ode">
<gravity>0.0 0.0 0.0</gravity>
<ode>
<solver>
<type>quick</type>
<iters>1500</iters>
<sor>1.0</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">
<pose>3.0 0 1.5 0 0 0</pose>
<inertial>
<pose>0.0 0 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>1.0</mass>
</inertial>
<collision name="collision">
<pose>0.0 0 0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</collision>
<visual name="visual">
<pose>0.0 0 0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</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_1">
<pose>3 0 1.5 0.1 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>1.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.1 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>1.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="body_joint" type="prismatic">
<parent>world</parent>
<child>body</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<xyz>1.0 0.0 0.0</xyz>
<dynamics>
<damping>0.000000</damping>
</dynamics>
</axis>
<physics>
<provide_feedback>true</provide_feedback>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<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>
<xyz>0 0.0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
<dynamics>
<damping>0.000000</damping>
</dynamics>
</axis>
<physics>
<provide_feedback>true</provide_feedback>
<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>
<xyz>0 0.0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
<dynamics>
<damping>0.000000</damping>
</dynamics>
</axis>
<physics>
<provide_feedback>true</provide_feedback>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
<plugin name="gazebo_wing_1" filename="libLiftDragPlugin.so">
<a0>0.1</a0>
<cla>4.000</cla>
<cda>20.0</cda>
<cma>0.00</cma>
<alpha_stall>10.0</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</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>20.0</cda>
<cma>0.00</cma>
<alpha_stall>10.0</alpha_stall>
<cla_stall>-0.2</cla_stall>
<cda_stall>1.0</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>
</model>
</world>
</sdf>