| <?xml version="1.0" encoding="UTF-8"?> |
| <robot name="gen3"> |
| <joint name="end_effector" type="fixed"> |
| <origin xyz="-0.061525 -0. 0. " rpy="3.1415927 0. -0. "/> |
| <parent link="bracelet_link"/> |
| <child link="end_effector_link"/> |
| </joint> |
| <joint name="joint_1" type="continuous"> |
| <origin xyz="0. 0. 0.15643" rpy="-1.5707964 1.5707891 1.5707964"/> |
| <parent link="base_link"/> |
| <child link="shoulder_link"/> |
| <axis xyz="1. 0. 0."/> |
| </joint> |
| <joint name="joint_2" type="revolute"> |
| <origin xyz="-0.12838 0.005375 0. " rpy="0. 0. -1.5708"/> |
| <parent link="shoulder_link"/> |
| <child link="half_arm_1_link"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-2.4099999" upper="2.4099999" effort="2340." velocity="1.3963"/> |
| </joint> |
| <joint name="joint_3" type="continuous"> |
| <origin xyz="-0.006375 -0.21038 0. " rpy="0. 0. 1.5707998"/> |
| <parent link="half_arm_1_link"/> |
| <child link="half_arm_2_link"/> |
| <axis xyz="1. 0. 0."/> |
| </joint> |
| <joint name="joint_4" type="revolute"> |
| <origin xyz="-0.21038 0.006375 0. " rpy="0. 0. -1.5707998"/> |
| <parent link="half_arm_2_link"/> |
| <child link="forearm_link"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-2.6599999" upper="2.6599999" effort="2340." velocity="1.3963"/> |
| </joint> |
| <joint name="joint_5" type="continuous"> |
| <origin xyz="-0.006375 -0.20843 0. " rpy="0. 0. 1.5707998"/> |
| <parent link="forearm_link"/> |
| <child link="spherical_wrist_1_link"/> |
| <axis xyz="1. 0. 0."/> |
| </joint> |
| <joint name="joint_6" type="revolute"> |
| <origin xyz="-0.10593 0.0001751 0. " rpy="0. 0. -1.5707998"/> |
| <parent link="spherical_wrist_1_link"/> |
| <child link="spherical_wrist_2_link"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-2.2299999" upper="2.2299999" effort="540." velocity="1.2218"/> |
| </joint> |
| <joint name="joint_7" type="continuous"> |
| <origin xyz="-0.0001751 -0.10593 0. " rpy="0. 0. 1.5707998"/> |
| <parent link="spherical_wrist_2_link"/> |
| <child link="bracelet_link"/> |
| <axis xyz="1. 0. 0."/> |
| </joint> |
| <joint name="root_joint" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="gen3"/> |
| <child link="base_link"/> |
| </joint> |
| <link name="base_link"> |
| <inertial> |
| <origin xyz="-0.000648 -0.000166 0.084487" rpy="0. 0. 0."/> |
| <mass value="1.697"/> |
| <inertia ixx="0.004622" ixy="0." ixz="0." iyy="0.004495" iyz="0." izz="0.002079"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/base_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/base_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="bracelet_link"> |
| <inertial> |
| <origin xyz="-0.000093 0.000132 -0.022905" rpy="0. 0. 0."/> |
| <mass value="0.364"/> |
| <inertia ixx="0.000214" ixy="0." ixz="0." iyy="0.000223" iyz="0." izz="0.00024"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="-0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/bracelet_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="-0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/bracelet_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="end_effector_link"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.0000001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| </link> |
| <link name="forearm_link"> |
| <inertial> |
| <origin xyz="-0.000018 -0.075478 -0.015006" rpy="0. 0. 0."/> |
| <mass value="0.9302"/> |
| <inertia ixx="0.008147" ixy="0." ixz="0." iyy="0.000631" iyz="0." izz="0.008316"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. -0. 0." rpy="0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/forearm_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. -0. 0." rpy="0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/forearm_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="gen3"/> |
| <link name="half_arm_1_link"> |
| <inertial> |
| <origin xyz="-0.000044 -0.09958 -0.013278" rpy="0. 0. 0."/> |
| <mass value="1.1636"/> |
| <inertia ixx="0.011088" ixy="0." ixz="0." iyy="0.001072" iyz="0." izz="0.011255"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/half_arm_1_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/half_arm_1_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="half_arm_2_link"> |
| <inertial> |
| <origin xyz="-0.000044 -0.006641 -0.117892" rpy="0. 0. 0."/> |
| <mass value="1.1636"/> |
| <inertia ixx="0.010932" ixy="0." ixz="0." iyy="0.011127" iyz="0." izz="0.001043"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="-0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/half_arm_2_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="-0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/half_arm_2_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="shoulder_link"> |
| <inertial> |
| <origin xyz="-0.000023 -0.010364 -0.07336 " rpy="0. 0. 0."/> |
| <mass value="1.3773"/> |
| <inertia ixx="0.00457" ixy="0." ixz="0." iyy="0.004831" iyz="0." izz="0.001409"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/shoulder_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="0. 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/shoulder_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="spherical_wrist_1_link"> |
| <inertial> |
| <origin xyz="0.000001 -0.009432 -0.063883" rpy="0. 0. 0."/> |
| <mass value="0.6781"/> |
| <inertia ixx="0.001596" ixy="0." ixz="0." iyy="0.001607" iyz="0." izz="0.000399"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="-0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/spherical_wrist_1_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="-0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/spherical_wrist_1_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="spherical_wrist_2_link"> |
| <inertial> |
| <origin xyz="0.000001 -0.045483 -0.00965 " rpy="0. 0. 0."/> |
| <mass value="0.6781"/> |
| <inertia ixx="0.001641" ixy="0." ixz="0." iyy="0.00041" iyz="0." izz="0.001641"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. 0. 0." rpy="0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/spherical_wrist_2_link_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. 0. 0." rpy="0.0000001 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/spherical_wrist_2_link_collisions_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </collision> |
| </link> |
| </robot> |
|
|