| 123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279 |
- <?xml version="1.0" encoding="UTF-8"?>
- <robot name="widowx" xmlns:xacro="http://ros.org/wiki/xacro">
-
- <material name="yellow">
- <color rgba="0.15 0.15 0.15 1.0"/>
- </material>
- <material name="white">
- <color rgba="0.86 0.85 0.81 1.0"/>
- </material>
- <material name="black">
- <color rgba="0.15 0.15 0.15 1.0"/>
- </material>
- <material name="grey">
- <color rgba="0.34 0.35 0.36 1.0"/>
- </material>
- <material name="greyish">
- <color rgba="0.75 0.75 0.75 1.0"/>
- </material>
-
-
-
- <link name="arm_base_link">
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/base_link.stl"/>
- </geometry>
- <material name="black"/>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/base_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value="13" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="shoulder_link">
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/shoulder_link.stl" />
- </geometry>
- <material name="greyish"/>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/shoulder_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="biceps_link">
- <visual>
- <origin xyz="0.04825 0 0.140" rpy="0 0 0" />
- <!--origin xyz="0 0 0" rpy="0 0 0" /-->
- <geometry>
- <mesh filename="meshes/biceps_link.stl" />
- </geometry>
- <material name="black"/>
- </visual>
- <collision>
- <origin xyz="0.04825 0 0.140" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/biceps_link.stl" />
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="forearm_link">
- <visual>
- <origin xyz="0 0 0.14203" rpy="0 0 0" />
- <!--origin xyz="0 0 0" rpy="0 0 0" /-->
- <geometry>
- <mesh filename="meshes/forearm_link.stl"/>
- </geometry>
- <material name="greyish"/>
- </visual>
- <collision>
- <origin xyz="0 0 0.14203" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/forearm_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <link name="wrist_1_link">
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/wrist_1_link.stl"/>
- </geometry>
- <material name="greyish"/>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/wrist_1_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="wrist_2_link">
- <visual>
- <origin xyz="0 0 0.043" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/wrist_2_link.stl"/>
- </geometry>
- <material name="black"/>
- </visual>
- <collision>
- <origin xyz="0 0 0.043" rpy="0 0 0" />
- <geometry>
- <mesh filename="meshes/wrist_2_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="gripper_rail_link">
- <visual>
- <origin xyz="0 0 0" rpy="0 0 1.57" />
- <geometry>
- <mesh filename="meshes/gripper_rail_link.stl"/>
- </geometry>
- <material name="greyish"/>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="0 0 1.57" />
- <geometry>
- <mesh filename="meshes/gripper_rail_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="gripper_aux_link">
- </link>
- <link name="gripper_1_link">
- <visual>
- <origin xyz="0 -0.0007 0" rpy="0 0 1.57" />
- <geometry>
- <mesh filename="meshes/gripper_hand_fixed_link.stl"/>
- </geometry>
- <material name="black"/>
- </visual>
- <collision>
- <origin xyz="0 -0.0007 0" rpy="0 0 1.57" />
- <geometry>
- <mesh filename="meshes/gripper_hand_fixed_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <link name="gripper_2_link">
- <visual>
- <origin xyz="0 0.0007 0" rpy="0 0 -1.57" />
- <geometry>
- <mesh filename="meshes/gripper_hand_fixed_link.stl"/>
- </geometry>
- <material name="greyish"/>
- </visual>
- <collision>
- <origin xyz="0 0.0007 0" rpy="0 0 -1.57" />
- <geometry>
- <mesh filename="meshes/gripper_hand_fixed_link.stl"/>
- </geometry>
- </collision>
- <inertial>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <mass value=".1" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
- </inertial>
- </link>
- <!-- joints -->
-
- <joint name="joint_1" type="revolute">
- <origin xyz="0 0 0.125" rpy="0 0 0" />
- <parent link="arm_base_link" />
- <child link="shoulder_link" />
- <axis xyz="0 0 1" />
- <limit lower="-2.617" upper="2.617" effort="0" velocity="0.785" />
- </joint>
- <joint name="joint_2" type="revolute">
- <!--origin xyz="0.04825 0 0.14203" rpy="0 0 0" /-->
- <origin xyz="0 0 0" rpy="0 0 0" />
- <parent link="shoulder_link" />
- <child link="biceps_link" />
- <axis xyz="0 1 0" />
- <limit lower="-1.571" upper="1.571" effort="0" velocity="1.571" />
- </joint>
- <joint name="joint_3" type="revolute">
- <origin xyz="0.04825 0 0.14203" rpy="0 1.5707963268 0" />
- <parent link="biceps_link" />
- <child link="forearm_link" />
- <axis xyz="0 1 0" />
- <limit lower="-1.571" upper="1.571" effort="0" velocity="1.571" />
- </joint>
- <joint name="joint_4" type="revolute">
- <origin xyz="0 0 0.14203" rpy="0 0 0" />
- <parent link="forearm_link" />
- <child link="wrist_1_link" />
- <axis xyz="0 1 0" />
- <limit lower="-1.745" upper="1.745" effort="0" velocity="1.571" />
- </joint>
- <joint name="joint_5" type="revolute">
- <origin xyz="0 0 0.0715" rpy="0 0 0" />
- <parent link="wrist_1_link" />
- <child link="wrist_2_link" />
- <axis xyz="0 0 1" />
- <limit lower="-2.617" upper="2.617" effort="0" velocity="1.571" />
- </joint>
- <joint name="joint_6" type="fixed">
- <origin xyz = "0 0 0.043" rpy="0 0 0" />
- <parent link="wrist_2_link" />
- <child link="gripper_rail_link" />
- <axis xyz="0 0 1" />
- <limit lower="-0.31" upper="0.1" effort="0" velocity="0.5" />
- </joint>
- <joint name="gripper_revolute_joint" type="revolute">
- <origin xyz = "0 0 0" rpy="0 0 0" />
- <parent link="gripper_rail_link" />
- <child link="gripper_aux_link" />
- <axis xyz="0 0 1" />
- <limit lower="0" upper="2.6" effort="0" velocity="0.5" />
- </joint>
- <joint name="gripper_prismatic_joint_1" type="prismatic">
- <origin xyz="0 0 0" rpy="0 0 0" />
- <parent link="gripper_rail_link" />
- <child link="gripper_1_link" />
- <axis xyz="0 -1 0" />
- <limit lower="0" upper="0.027" effort="0" velocity="0.5" />
- </joint>
- <joint name="gripper_prismatic_joint_2" type="prismatic">
- <origin xyz="0 0 0" rpy="0 0 0" />
- <parent link="gripper_rail_link" />
- <child link="gripper_2_link" />
- <mimic joint="gripper_prismatic_joint_1" />
- <axis xyz="0 1 0" />
- <limit lower="0" upper="0.027" effort="0" velocity="0.5" />
- </joint>
- </robot>
|