Last active
August 12, 2019 06:06
-
-
Save pythongo1/c64868cdd316077eb80abbd9be247ab9 to your computer and use it in GitHub Desktop.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<!-- Revolute-Revolute Manipulator --> | |
<robot name="rrbot" xmlns:xacro="http://www.ros.org/wiki/xacro"> | |
<!-- Constants for robot dimensions --> | |
<xacro:property name="PI" value="3.1415926535897931"/> | |
<xacro:property name="mass" value="1" /> <!-- arbitrary value for mass --> | |
<xacro:property name="width" value="0.1" /> <!-- Square dimensions (widthxwidth) of beams --> | |
<xacro:property name="height1" value="2" /> <!-- Link 1 --> | |
<xacro:property name="height2" value="1" /> <!-- Link 2 --> | |
<xacro:property name="height3" value="1" /> <!-- Link 3 --> | |
<xacro:property name="camera_link" value="0.05" /> <!-- Size of square 'camera' box --> | |
<xacro:property name="axel_offset" value="0.05" /> <!-- Space btw top of beam and the each joint --> | |
<!-- Import all Gazebo-customization elements, including Gazebo colors --> | |
<xacro:include filename="$(find rrbot_description)/urdf/rrbot.gazebo" /> | |
<!-- Import Rviz colors --> | |
<xacro:include filename="$(find rrbot_description)/urdf/materials.xacro" /> | |
<!-- for fixing the robot --> | |
<link name="world"/> | |
<joint name="fixed" type="fixed"> | |
<parent link="world"/> | |
<child link="empty_base"/> | |
</joint> | |
<!-- no use base --> | |
<link name="empty_base"> | |
<visual> | |
<origin xyz="0 0 0.005"/> | |
<geometry> | |
<box size="0.01 0.01 0.01"/> <!-- for big a bit --> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<joint name="empty_base_to_hand_base" type="fixed"> | |
<parent link="empty_base"/> | |
<child link="hand_base"/> | |
<origin xyz="0 0 0.1" rpy="0 0 0"/> <!-- for rotate --> | |
</joint> | |
<!-- real hand base --> | |
<link name="hand_base"> | |
<visual> | |
<origin xyz="0 0.05 0"/> | |
<geometry> | |
<box size="0.05 0.1 0.01"/> <!-- for big a bit --> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- for finger5 --> <!-- change to continuous --> | |
<joint name="hand_base_to_finger5" type="continuous"> | |
<parent link="hand_base"/> | |
<child link="finger5"/> | |
<origin xyz="-0.02861 0.11081 0.00842 " rpy="0 ${2*PI/360*7} ${2*PI/360*6}"/> | |
<axis xyz="1 0 0"/> <!-- origin 1 0 0 --> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger5"> | |
<visual> | |
<origin xyz="0 0.01775 0"/> | |
<geometry> | |
<box size="0.008 0.0355 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- I change fixed to continuous , and the color successfully change... --> | |
<joint name="finger5_to_finger5_1" type="continuous"> | |
<parent link="finger5"/> | |
<child link="finger5_1"/> | |
<origin xyz="0 0.0355 0" rpy="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger5_1"> | |
<visual> | |
<origin xyz="0 0.018125 0"/> | |
<geometry> | |
<box size="0.008 0.03625 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- for finger4 --> | |
<joint name="hand_base_to_finger4" type="continuous"> | |
<parent link="hand_base"/> | |
<child link="finger4"/> | |
<origin xyz="-0.01267 0.11495 0.01139" rpy="0 ${2*PI/360*3} ${2*PI/360*2.5}"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger4"> | |
<visual> | |
<origin xyz="0 0.01975 0"/> | |
<geometry> | |
<box size="0.008 0.0395 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<joint name="finger4_to_finger4_1" type="continuous"> | |
<parent link="finger4"/> | |
<child link="finger4_1"/> | |
<origin xyz="0 0.0355 0" rpy="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger4_1"> | |
<visual> | |
<origin xyz="0 0.02201 0"/> | |
<geometry> | |
<box size="0.008 0.04402 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- for finger3 , middle finger --> | |
<joint name="hand_base_to_finger3" type="continuous"> | |
<parent link="hand_base"/> | |
<child link="finger3"/> | |
<origin xyz="0.012 0.11629 0.01158" rpy="0 0 ${-2*PI/360*1}"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger3"> | |
<visual> | |
<origin xyz="0 0.0215 0"/> | |
<geometry> | |
<box size="0.008 0.043 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<joint name="finger3_to_finger3_1" type="continuous"> | |
<parent link="finger3"/> | |
<child link="finger3_1"/> | |
<origin xyz="0 0.043 0" rpy="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger3_1"> | |
<visual> | |
<origin xyz="0 0.024 0"/> | |
<geometry> | |
<box size="0.008 0.048 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- for finger2, index finger, eat finger --> | |
<joint name="hand_base_to_finger2" type="continuous"> | |
<parent link="hand_base"/> | |
<child link="finger2"/> | |
<origin xyz="0.03286 0.11382 0.00806" rpy="0 ${2*PI/360*5} ${-2*PI/360*4}"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger2"> | |
<visual> | |
<origin xyz="0 0.01775 0"/> | |
<geometry> | |
<box size="0.008 0.0355 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<joint name="finger2_to_finger2_1" type="continuous"> | |
<parent link="finger2"/> | |
<child link="finger2_1"/> | |
<origin xyz="0 0.0355 0" rpy="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger2_1"> | |
<visual> | |
<origin xyz="0 0.024 0"/> | |
<geometry> | |
<box size="0.008 0.048 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- for finger1, thumb , big finger --> | |
<!-- note finger1 has a rotate axis --> | |
<joint name="hand_base_to_finger1_rotate_axis" type="continuous"> | |
<parent link="hand_base"/> | |
<child link="finger1_rotate_axis"/> | |
<origin xyz="0.01587 0 0.01582" rpy="0 0 0"/> <!-- maybe is negative --> | |
<axis xyz="0 1 0"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger1_rotate_axis"> | |
<visual> | |
<origin xyz="0.001 0 0"/> | |
<geometry> | |
<box size="0.002 0.002 0.002"/> <!-- use a square to present, position arbitrary --> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<joint name="finger1_rotate_axis_to_finger1" type="fixed"> | |
<parent link="finger1_rotate_axis"/> | |
<child link="finger1"/> | |
<origin xyz="0.01504 0 0.00679" rpy="0 0 0"/> | |
</joint> | |
<link name="finger1"> | |
<visual> | |
<origin xyz="0 0.03669 0"/> | |
<geometry> | |
<box size="0.008 0.07338 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<joint name="finger1_to_finger1_1" type="continuous"> | |
<parent link="finger1"/> | |
<child link="finger1_1"/> | |
<origin xyz="0 0.07338 0" rpy="0 0 0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="30" velocity="1"/> | |
</joint> | |
<link name="finger1_1"> | |
<visual> | |
<origin xyz="0 0.0135 0"/> | |
<geometry> | |
<box size="0.008 0.027 0.008"/> | |
</geometry> | |
<material name="black"/> | |
</visual> | |
<inertial> | |
<origin xyz="0 0 0"/> | |
<mass value="1"/> | |
<inertia | |
ixx="0.01" ixy="0.0" ixz="0.0" | |
iyy="0.01" iyz="0.0" | |
izz="0.01"/> | |
</inertial> | |
</link> | |
<!-- transmission finger5 --> | |
<transmission name="finger5_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger5_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="hand_base_to_finger5"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<transmission name="finger5_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger5_1_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="finger5_to_finger5_1"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<!-- transmission finger4 --> | |
<transmission name="finger4_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger4_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="hand_base_to_finger4"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<transmission name="finger4_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger4_1_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="finger4_to_finger4_1"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<!-- transmission finger3 --> | |
<transmission name="finger3_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger3_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="hand_base_to_finger3"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<transmission name="finger3_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger3_1_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="finger3_to_finger3_1"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<!-- transmission finger2 --> | |
<transmission name="finger2_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger2_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="hand_base_to_finger2"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<transmission name="finger2_1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger2_1_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="finger2_to_finger2_1"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<!-- for finger1 rotate axis --> | |
<transmission name="finger1_rotate_axis_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger1_rotate_axis_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="hand_base_to_finger1_rotate_axis"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
<!-- for finger1 trans --> | |
<transmission name="finger1_trans"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<actuator name="finger1_motor"> | |
<mechanicalReduction>1</mechanicalReduction> | |
</actuator> | |
<joint name="finger1_to_finger1_1"> | |
<hardwareInterface>PositionJointInterface</hardwareInterface> | |
</joint> | |
</transmission> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment