oscillation_ctrl/models/spiri_with_tether/spiri_with_tether.sdf

188 lines
5.0 KiB
XML

<!-- DO NOT EDIT: Generated from spiri_with_tether.sdf.jinja -->
<!-- tl = 0.8 num. of el. = 1 payload sz: 0.025-->
<sdf version="1.5">
<model name="spiri_with_tether">
<pose> 0 0 0 0.0 0.0 0.0</pose>
<include>
<uri>model://spiri</uri>
<pose>0.0 0.0 0.0 0.0 0.0 0</pose>
<static>0</static>
</include>
<joint name="tether_to_spiri_joint" type="ball">
<child>link_spiri_attch</child>
<parent>spiri::base</parent><pose>0 0 -0.4 0 0 0 </pose>
<physics>
<ode></ode>
<provide_feedback>true</provide_feedback>
</physics>
</joint>
<plugin name="ft_sensor_spiri" filename="libgazebo_ros_ft_sensor.so">
<updateRate>1.0</updateRate>
<topicName>ft_sensor_topic/spiri</topicName>
<jointName>tether_to_spiri_joint</jointName>
</plugin>
<link name="link_spiri_attch">
<gravity>true</gravity>
<pose>0.4 0.0 0 0.0 1.5707 0.0</pose>
<inertial>
<mass>0.004</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>0.0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.8</length>
<radius>0.005</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.00005</min_depth>
</ode>
</contact>
<friction>
<ode>
<mu>1.0</mu>
<mu2>1.0</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="element_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.8</length>
<radius>0.005</radius>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/White</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual><visual name="sphere_visual">
<pose> 0 0 -0.4 0 0 0 </pose>
<geometry>
<sphere>
<radius>0.01</radius>
</sphere>
</geometry>
<material>
<script>
<name>Gazebo/Red</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
</link>
<plugin name="link_spiri_attch_drag" filename="libLiftDragPlugin.so">
<robotNamespace></robotNamespace>
<a0>0</a0>
<cla>0</cla>
<cda>1.253582</cda>
<alpha_stall>0</alpha_stall>
<cda_stall>1.4326647564469914</cda_stall>
<useConstantDragCoefficient>true</useConstantDragCoefficient>
<cp>0.4 0.005 0.005</cp>
<area>0.008</area>
<air_density>1.2041</air_density>
<forward>0 1 0</forward>
<upward>0 0 1</upward>
<link_name>link_spiri_attch</link_name>
</plugin>
<!-- PAYLOAD -->
<model name='mass'>
<link name="payload">
<pose> 0.8 0 0 0 0 0</pose>
<!--pose>0 0 0 0 0 0</pose-->
<gravity>1</gravity>
<inertial>
<mass>0.25</mass>
</inertial>
<collision name="payload_collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.025</radius>
</sphere>
</geometry>
</collision>
<visual name="payload_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.025</radius>
</sphere>
</geometry>
</visual>
</link>
<!-- Tether to Payload Connection -->
<joint name="tether_mass_connection" type="fixed">
<parent>payload</parent>
<child>link_spiri_attch</child>
<pose>0 0 0.4 0 0 0</pose>
<physics>
<ode></ode>
<provide_feedback>true</provide_feedback>
</physics>
</joint>
<!--/model--><link name='pload_imu'>
<pose>0.8 0 0 0 0 0</pose>
<inertial>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
</link>
<joint name='pload_imu_joint' type='revolute'>
<child>pload_imu</child>
<parent>payload</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>0</use_parent_model_frame>
</axis>
</joint>
<plugin name='imu_plugin' filename='libgazebo_ros_imu.so'>
<robotNamespace/>
<alwaysOn>true</alwaysOn>
<bodyName>pload_imu</bodyName>
<topicName>/pload_imu</topicName>
<serviceName>imu_service</serviceName>
<gaussianNoise>0.0</gaussianNoise>
<updateRate>20.0</updateRate>
</plugin>
</model>
</model>
</sdf>
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=2 ts=2 : -->