gazebo_models/youbot/model-1_2.sdf
2013-04-12 08:06:42 -07:00

1420 lines
42 KiB
XML

<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="youbot">
<pose>0 0 0.09 0 0 0</pose>
<link name="base_footprint">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 -0.050000 0 0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>0.100000</mass>
</inertial>
<collision name="base_footprint_geom">
<pose>0 0 -0.050000 0 0 0</pose>
<geometry>
<box>
<size>0.001000 0.001000 0.001000</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="base_footprint_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.001000 0.001000 0.001000</size>
</box>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="base_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>5.652230</ixx>
<ixy>-0.009720</ixy>
<ixz>1.293990</ixz>
<iyy>5.669470</iyy>
<iyz>-0.007380</iyz>
<izz>3.683200</izz>
</inertia>
<mass>22.000000</mass>
</inertial>
<collision name="base_link_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/base/base_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="base_link_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/base/base.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="arm_link_0">
<pose>0.143000 0 0.046000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.010000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.010000</iyy>
<iyz>0</iyz>
<izz>0.010000</izz>
</inertia>
<mass>0.845000</mass>
</inertial>
<collision name="arm_link_0_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm0_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="arm_link_0_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm0.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://youbot/materials/scripts/youbot.material</uri>
<name>youbot/DarkGrey</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="arm_link_1">
<pose>0.167000 0 0.142000 0 0 2.967060</pose>
<inertial>
<pose>0.014890 0.002130 0.002130 0 0 0</pose>
<inertia>
<ixx>0.003863</ixx>
<ixy>-0.000979</ixy>
<ixz>0</ixz>
<iyy>0.006196</iyy>
<iyz>0</iyz>
<izz>0.006369</izz>
</inertia>
<mass>2.412000</mass>
</inertial>
<collision name="arm_link_1_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm1_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="arm_link_1_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm1.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="arm_link_2">
<pose>0.134501 0.005730 0.161000 0 -1.134460 2.967060</pose>
<inertial>
<pose>0.104530 0.001700 -0.002970 0 0 0</pose>
<inertia>
<ixx>0.000823</ixx>
<ixy>0</ixy>
<ixz>-0.000000</ixz>
<iyy>0.004447</iyy>
<iyz>0</iyz>
<izz>0.004439</izz>
</inertia>
<mass>1.155000</mass>
</inertial>
<collision name="arm_link_2_geom">
<pose>0 -0.032000 0.078000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm2_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="arm_link_2_geom_visual">
<pose>0 -0.032000 0.078000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm2.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="arm_link_3">
<pose>0.272845 -0.018663 0.226506 0 1.413720 2.967060</pose>
<inertial>
<pose>0.000100 0.096700 0.021070 0 0 0</pose>
<inertia>
<ixx>0.002459</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.002571</iyy>
<iyz>-0.000000</iyz>
<izz>0.000535</izz>
</inertia>
<mass>0.934000</mass>
</inertial>
<collision name="arm_link_3_geom">
<pose>0 0.028000 0.079000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm3_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="arm_link_3_geom_visual">
<pose>0 0.028000 0.079000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm3.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="arm_link_4">
<pose>0.141533 0.004491 0.247624 0 -0.375246 2.967060</pose>
<inertial>
<pose>0.000110 0.051030 -0.023190 0 0 0</pose>
<inertia>
<ixx>0.000869</ixx>
<ixy>0</ixy>
<ixz>-0.000000</ixz>
<iyy>0.001173</iyy>
<iyz>-0.000231</iyz>
<izz>0.001091</izz>
</inertia>
<mass>0.877000</mass>
</inertial>
<collision name="arm_link_4_geom">
<pose>0 -0.010000 0.029000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm4_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="arm_link_4_geom_visual">
<pose>0 -0.010000 0.029000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm4.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="arm_link_5">
<pose>0.190287 -0.004106 0.367846 -0.085052 0.365926 -0.408445</pose>
<inertial>
<pose>0 0.001150 -0.016830 0 0 0</pose>
<inertia>
<ixx>0.000280</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000339</iyy>
<iyz>0</iyz>
<izz>0.000119</izz>
</inertia>
<mass>0.251000</mass>
</inertial>
<collision name="arm_link_5_geom">
<pose>0.003000 0 -0.034000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm5_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="arm_link_5_geom_visual">
<pose>0.003000 0 -0.034000 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm5.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="gripper_palm_link">
<pose>0.190287 -0.004106 0.367846 -0.085052 0.365926 -0.408445</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.010000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.010000</iyy>
<iyz>0</iyz>
<izz>0.010000</izz>
</inertia>
<mass>0.100000</mass>
</inertial>
<collision name="gripper_palm_link_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/palm_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="gripper_palm_link_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/palm.stl</uri>
</mesh>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Black</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<self_collide>1</self_collide>
<kinematic>0</kinematic>
</link>
<link name="gripper_finger_link_l">
<pose>0.213260 -0.001105 0.408579 0.085052 -0.365926 2.733150</pose>
<inertial>
<pose>0 -0.001000 0 0 0 0</pose>
<inertia>
<ixx>0.010000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.010000</iyy>
<iyz>0</iyz>
<izz>0.010000</izz>
</inertia>
<mass>0.010000</mass>
</inertial>
<collision name="gripper_finger_link_l_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="gripper_finger_link_l_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger.stl</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="gripper_finger_link_r">
<pose>0.207375 -0.015929 0.409848 -0.085052 0.365926 -0.408445</pose>
<inertial>
<pose>0 -0.001000 0 0 0 0</pose>
<inertia>
<ixx>0.010000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.010000</iyy>
<iyz>0</iyz>
<izz>0.010000</izz>
</inertia>
<mass>0.010000</mass>
</inertial>
<collision name="gripper_finger_link_r_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="gripper_finger_link_r_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger.stl</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="base_laser_front_link">
<pose>0.300000 0 -0.030000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.100000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.100000</iyy>
<iyz>0</iyz>
<izz>0.100000</izz>
</inertia>
<mass>0.160000</mass>
</inertial>
<collision name="base_laser_front_link_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="base_laser_front_link_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="base_laser_front" type="ray">
<pose>0 0 0 0 0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-1.570000</min_angle>
<max_angle>1.570000</max_angle>
</horizontal>
</scan>
<range>
<min>0.050000</min>
<max>5.600000</max>
<resolution>0.360000</resolution>
</range>
</ray>
<always_on>0</always_on>
<update_rate>10.000000</update_rate>
<visualize>0</visualize>
</sensor>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="caster_link_bl">
<pose>-0.228000 0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.100000</mass>
</inertial>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="wheel_link_bl">
<pose>-0.228000 0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.400000</mass>
</inertial>
<collision name="wheel_link_bl_geom">
<pose>0 0 0 1.570800 0 0</pose>
<geometry>
<cylinder>
<radius>0.050000</radius>
<length>0.005000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="wheel_link_bl_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/base/back-left_wheel.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://youbot/materials/scripts/youbot.material</uri>
<name>youbot/Orange</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="caster_link_br">
<pose>-0.228000 -0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.100000</mass>
</inertial>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="wheel_link_br">
<pose>-0.228000 -0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.400000</mass>
</inertial>
<collision name="wheel_link_br_geom">
<pose>0 0 0 1.570800 0 0</pose>
<geometry>
<cylinder>
<radius>0.050000</radius>
<length>0.005000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="wheel_link_br_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/base/back-right_wheel.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://youbot/materials/scripts/youbot.material</uri>
<name>youbot/Orange</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="caster_link_fl">
<pose>0.228000 0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.100000</mass>
</inertial>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="wheel_link_fl">
<pose>0.228000 0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.400000</mass>
</inertial>
<collision name="wheel_link_fl_geom">
<pose>0 0 0 1.570800 0 0</pose>
<geometry>
<cylinder>
<radius>0.050000</radius>
<length>0.005000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="wheel_link_fl_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/base/front-left_wheel.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://youbot/materials/scripts/youbot.material</uri>
<name>youbot/Orange</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="caster_link_fr">
<pose>0.228000 -0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.100000</mass>
</inertial>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="wheel_link_fr">
<pose>0.228000 -0.158000 -0.034000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.012412</ixx>
<ixy>-0.000712</ixy>
<ixz>0.000503</ixz>
<iyy>0.015218</iyy>
<iyz>-0.000004</iyz>
<izz>0.011764</izz>
</inertia>
<mass>0.400000</mass>
</inertial>
<collision name="wheel_link_fr_geom">
<pose>0 0 0 1.570800 0 0</pose>
<geometry>
<cylinder>
<radius>0.050000</radius>
<length>0.005000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="wheel_link_fr_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/base/front-right_wheel.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://youbot/materials/scripts/youbot.material</uri>
<name>youbot/Orange</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<link name="plate_link">
<pose>-0.159000 0 0.046000 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.010000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.010000</iyy>
<iyz>0</iyz>
<izz>0.010000</izz>
</inertia>
<mass>1</mass>
</inertial>
<collision name="plate_link_geom">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/plate/plate_convex.stl</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.200000</soft_erp>
<kp>10000000000000.000000</kp>
<kd>100000000000.000000</kd>
<max_vel>-1</max_vel>
<min_depth>0</min_depth>
</ode>
</contact>
</surface>
<laser_retro>0</laser_retro>
</collision>
<visual name="plate_link_geom_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://youbot/meshes/plate/plate.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<joint name="base_footprint_joint" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_footprint</parent>
<child>base_link</child>
<axis>
<dynamics>
<damping>0</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="arm_joint_0" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>arm_link_0</child>
<axis>
<dynamics>
<damping>0</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="arm_joint_1" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>arm_link_0</parent>
<child>arm_link_1</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>5.899213</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 -1</xyz>
</axis>
</joint>
<joint name="arm_joint_2" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>arm_link_1</parent>
<child>arm_link_2</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>2.705260</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>-0.173648 -0.984808 0</xyz>
</axis>
</joint>
<joint name="arm_joint_3" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>arm_link_2</parent>
<child>arm_link_3</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-5.183628</lower><upper>0</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>-0.173648 -0.984808 0</xyz>
</axis>
</joint>
<joint name="arm_joint_4" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>arm_link_3</parent>
<child>arm_link_4</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>3.577925</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>-0.173648 -0.984808 0</xyz>
</axis>
</joint>
<joint name="arm_joint_5" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>arm_link_4</parent>
<child>arm_link_5</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>5.846853</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>-0.360933 0.063642 -0.930418</xyz>
</axis>
</joint>
<joint name="gripper_palm_joint" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>arm_link_5</parent>
<child>gripper_palm_link</child>
<axis>
<dynamics>
<damping>0</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="gripper_finger_joint_l" type="prismatic">
<pose>0 0 0 0 0 0</pose>
<parent>gripper_palm_link</parent>
<child>gripper_finger_link_l</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0.011500</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0.367852 0.926495 -0.079325</xyz>
</axis>
</joint>
<joint name="gripper_finger_joint_r" type="prismatic">
<pose>0 0 0 0 0 0</pose>
<parent>gripper_palm_link</parent>
<child>gripper_finger_link_r</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0.011500</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>-0.367852 -0.926495 0.079325</xyz>
</axis>
</joint>
<joint name="base_laser_front_hokuyo_urg04_laser_joint" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>base_laser_front_link</child>
<axis>
<dynamics>
<damping>0</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="caster_joint_bl" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>caster_link_bl</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="wheel_joint_bl" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>caster_link_bl</parent>
<child>wheel_link_bl</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 1.000000 0</xyz>
</axis>
</joint>
<joint name="caster_joint_br" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>caster_link_br</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="wheel_joint_br" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>caster_link_br</parent>
<child>wheel_link_br</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 1.000000 0</xyz>
</axis>
</joint>
<joint name="caster_joint_fl" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>caster_link_fl</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="wheel_joint_fl" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>caster_link_fl</parent>
<child>wheel_link_fl</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 1.000000 0</xyz>
</axis>
</joint>
<joint name="caster_joint_fr" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>caster_link_fr</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="wheel_joint_fr" type="revolute">
<pose>0 0 0 0 0 0</pose>
<parent>caster_link_fr</parent>
<child>wheel_link_fr</child>
<axis>
<dynamics>
<damping>1</damping>
<friction>0</friction>
</dynamics>
<limit><lower>-10000000000000000.000000</lower><upper>10000000000000000.000000</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 1.000000 0</xyz>
</axis>
</joint>
<joint name="plate_joint" type="revolute">
<parent>base_link</parent>
<child>plate_link</child>
<axis>
<dynamics>
<damping>0</damping>
<friction>0</friction>
</dynamics>
<limit><lower>0</lower><upper>0</upper><effort>0</effort><velocity>0</velocity></limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<static>0</static>
</model>
</gazebo>