2023-06-27 12:18:48 +00:00

334 lines
10 KiB
XML

<?xml version="1.0" ?>
<robot name="iisy">
<link name="world"/>
<link name="base_link"/>
<link name="table">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/table.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/table.stl"/>
</geometry>
</visual>
</link>
<link name="base_bottom">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/base_bottom_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/base_bottom_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="-0.043517 0.000000 0.054914"/>
<mass value="6"/>
<inertia ixx="1.277905" ixy="0.0" ixz="0.138279" iyy="3.070705" iyz="0.0" izz="3.284356"/>
</inertial>
</link>
<link name="base_top">
<collision>
<origin xyz="0 -0.005 0.08"/>
<geometry>
<box size="0.14 0.15 0.16"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/base_top_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 -0.005 0.08"/>
<mass value="2"/>
<inertia ixx="0.32666666666667" ixy="0.0" ixz="0.0" iyy="0.32666666666667" iyz="0.0" izz="0.25"/>
</inertial>
</link>
<link name="link1_full">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_1_full_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_1_full_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 -0.050000 0.150000"/>
<mass value="4"/>
<inertia ixx="8.266347" ixy="0.0" ixz="0.0" iyy="8.647519" iyz="0.0" izz="8.647519"/>
</inertial>
</link>
<link name="link2_bottom">
<collision>
<origin xyz="0 0.07 0.025"/>
<geometry>
<box size="0.14 0.14 0.19"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_2_bottom_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0.07 0.025"/>
<mass value="2"/>
<inertia ixx="0.5" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="0.25"/>
</inertial>
</link>
<link name="link2_top">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_2_top_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_2_top_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0.037363 0.086674"/>
<mass value="2"/>
<inertia ixx="1.431738" ixy="0.0" ixz="0.0" iyy="1.131426" iyz="-0.342192" izz="0.807202"/>
</inertial>
</link>
<link name="link3_bottom">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_3_bottom_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_3_bottom_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 -0.055000 0.021413"/>
<mass value="2"/>
<inertia ixx="0.362124" ixy="0.0" ixz="0.0" iyy="0.343531" iyz="0.0" izz="0.283368"/>
</inertial>
</link>
<link name="link3_top">
<collision>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_3_top_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file://$(find iisy_config)/stl/link_3_top_low.stl"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 -0.015462 0.040000"/>
<mass value="0.8"/>
<inertia ixx="0.228470" ixy="0.0" ixz="0.0" iyy="0.137641" iyz="0.0" izz="0.252003"/>
</inertial>
</link>
<joint name="world_base_link_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
<joint name="base_base_link_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="table"/>
</joint>
<joint name="table_link_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 1"/>
<parent link="table"/>
<child link="base_bottom"/>
</joint>
<joint name="base_rot" type="continuous">
<origin rpy="0 0 0" xyz="0 0 0.1205"/>
<parent link="base_bottom"/>
<child link="base_top"/>
<axis xyz="0 0 1"/>
<limit effort="300" velocity="3.49065850399"/>
<dynamics damping="30.0" friction="0.1"/>
</joint>
<joint name="base_link1_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.080499 0.092997"/>
<parent link="base_top"/>
<child link="link1_full"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="-2.2689280275926" upper="2.4434609527921" velocity="3.49065850399"/>
<dynamics damping="30.0" friction="0.1"/>
</joint>
<joint name="link1_link2_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.3"/>
<parent link="link1_full"/>
<child link="link2_bottom"/>
<axis xyz="0 1 0"/>
<limit effort="200" lower="-2.6179938779915" upper="2.6179938779915" velocity="3.49065850399"/>
<dynamics damping="20.0" friction="0.1"/>
</joint>
<joint name="link2_rot" type="continuous">
<origin rpy="0 0 0" xyz="0 0.080501 0.120502"/>
<parent link="link2_bottom"/>
<child link="link2_top"/>
<axis xyz="0 0 1"/>
<limit effort="100" velocity="5.23598775598"/>
<dynamics damping="10.0" friction="0.1"/>
</joint>
<joint name="link2_link3_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0.0565 0.178003"/>
<parent link="link2_top"/>
<child link="link3_bottom"/>
<axis xyz="0 1 0"/>
<limit effort="50" velocity="5.23598775598"/>
<dynamics damping="5.0" friction="0.1"/>
</joint>
<joint name="link3_rot" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.055001 0.085501"/>
<parent link="link3_bottom"/>
<child link="link3_top"/>
<axis xyz="0 0 1"/>
<limit effort="50" velocity="6.98131700798"/>
<dynamics damping="5.0" friction="0.1"/>
</joint>
<transmission name="trans_base_rot">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_rot">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="base_rot_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="trans_base_link1_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_link1_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="base_link1_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="trans_link1_link2_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="link1_link2_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link1_link2_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="trans_link2_rot">
<type>transmission_interface/SimpleTransmission</type>
<joint name="link2_rot">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link2_rot_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="trans_link2_link3_joint">
<type>transmission_interface/SimpleTransmission</type>
<joint name="link2_link3_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link2_link3_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="trans_link3_rot">
<type>transmission_interface/SimpleTransmission</type>
<joint name="link3_rot">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link3_rot_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="table">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>0.8 0.8 0.8 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="base_bottom">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>0.5 0.5 0.5 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="base_top">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>1 0.35 0 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="link1_full">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>1 0.35 0 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="link2_bottom">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>1 0.35 0 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="link2_top">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>1 0.35 0 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="link3_bottom">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>1 0.35 0 1 </diffuse>
</material>
</visual>
</gazebo>
<gazebo reference="link3_top">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<diffuse>0.5 0.5 0.5 1 </diffuse>
</material>
</visual>
</gazebo>
</robot>