Newer
Older
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ur10_joint_limited_robot.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="ur10" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- common stuff -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="ros_control">
<!--robotNamespace>/</robotNamespace-->
<!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
<!--
<plugin name="gazebo_ros_power_monitor_controller" filename="libgazebo_ros_power_monitor.so">
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<timeout>5</timeout>
<powerStateTopic>power_state</powerStateTopic>
<powerStateRate>10.0</powerStateRate>
<dischargeRate>-474</dischargeRate>
<chargeRate>525</chargeRate>
<dischargeVoltage>15.52</dischargeVoltage>
<chargeVoltage>16.41</chargeVoltage>
</plugin>
</gazebo>
<!-- ur10 -->
<!-- arm -->
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Base.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/>
</geometry>
</collision>
<inertial>
<mass value="4.0"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
</inertial>
</link>
<joint name="shoulder_pan_joint" type="revolute">
<parent link="base_link"/>
<child link="shoulder_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1273"/>
<limit effort="330.0" lower="-3.14159265" upper="3.14159265" velocity="2.16"/>
</joint>
<link name="shoulder_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Shoulder.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/>
<mass value="7.778"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0314743125769" ixy="0.0" ixz="0.0" iyy="0.0314743125769" iyz="0.0" izz="0.021875625"/>
</inertial>
</link>
<joint name="shoulder_lift_joint" type="revolute">
<parent link="shoulder_link"/>
<child link="upper_arm_link"/>
<origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.220941 0.0"/>
<limit effort="330.0" lower="-3.14159265" upper="3.14159265" velocity="2.16"/>
</joint>
<link name="upper_arm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/UpperArm.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/upper_arm.stl"/>
<mass value="12.93"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.306"/>
<inertia ixx="0.421753803798" ixy="0.0" ixz="0.0" iyy="0.421753803798" iyz="0.0" izz="0.036365625"/>
</inertial>
</link>
<joint name="elbow_joint" type="revolute">
<parent link="upper_arm_link"/>
<child link="forearm_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.1719 0.612"/>
<limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.15"/>
</joint>
<link name="forearm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Forearm.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
<mass value="3.87"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.28615"/>
<inertia ixx="0.111069694097" ixy="0.0" ixz="0.0" iyy="0.111069694097" iyz="0.0" izz="0.010884375"/>
</inertial>
</link>
<joint name="wrist_1_joint" type="revolute">
<parent link="forearm_link"/>
<child link="wrist_1_link"/>
<origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.0 0.5723"/>
<limit effort="54.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
</joint>
<link name="wrist_1_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Wrist1.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/wrist_1.stl"/>
<mass value="1.96"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125"/>
</inertial>
</link>
<joint name="wrist_2_joint" type="revolute">
<parent link="wrist_1_link"/>
<child link="wrist_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.1149 0.0"/>
<limit effort="54.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
</joint>
<link name="wrist_2_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Wrist2.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/wrist_2.stl"/>
<mass value="1.96"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125"/>
</inertial>
</link>
<joint name="wrist_3_joint" type="revolute">
<parent link="wrist_2_link"/>
<child link="wrist_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1157"/>
<limit effort="54.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
</joint>
<link name="wrist_3_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Wrist3.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/wrist_3.stl"/>
<mass value="0.202"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.000526462289415" ixy="0.0" ixz="0.0" iyy="0.000526462289415" iyz="0.0" izz="0.000568125"/>
</inertial>
</link>
<joint name="ee_fixed_joint" type="fixed">
<parent link="wrist_3_link"/>
<child link="ee_link"/>
<origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0922 0.0"/>
<link name="ee_link">
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.01 0 0"/>
</collision>
</link>
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
<transmission name="shoulder_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_pan_joint"/>
<actuator name="shoulder_pan_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="shoulder_lift_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_lift_joint"/>
<actuator name="shoulder_lift_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="elbow_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="elbow_joint"/>
<actuator name="elbow_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_1_joint"/>
<actuator name="wrist_1_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_2_joint"/>
<actuator name="wrist_2_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_3_joint"/>
<actuator name="wrist_3_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="world_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>