| <?xml version="1.0"?> |
| <robot name="bravo7_no_ee"> |
|
|
| <material name="green"> |
| <color rgba="0.235 0.702 0.443 1"/> |
| </material> |
|
|
| <material name="blue"> |
| <color rgba="0.263 0.733 0.984 1"/> |
| </material> |
|
|
| <material name="red"> |
| <color rgba="1 0 0 1"/> |
| </material> |
|
|
| <material name="black"> |
| <color rgba="0.8 0.8 0.8 1"/> |
| </material> |
|
|
| <material name="orange"> |
| <color rgba="1 0.369 0.047 1"/> |
| </material> |
|
|
| <link name="link1"> |
| <visual> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-266.stl"/> |
| </geometry> |
| <material name="blue"/> |
| </visual> |
| <inertial> |
| <mass value="1.25"/> |
| <origin xyz="-0.075 -0.006 -0.003"/> |
| <inertia ixx="0.002108" ixy="0.000182" ixz="-0.000015" iyy="0.002573" iyz="-0.000021" izz="0.003483"/> |
| </inertial> |
| <collision> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-266_convex_hull.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="joint1" type="continuous"> |
| <parent link="link1"/> |
| <child link="link2"/> |
| <origin rpy="3.141592654 0 0" xyz="0.0665 0 0.078"/> |
| <axis xyz="0 0 1"/> |
| </joint> |
|
|
| <link name="link2"> |
| <visual> |
| <origin xyz="0 0 0" rpy="-3.141592654 0 0"/> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-217.stl"/> |
| </geometry> |
| <material name="green"/> |
| </visual> |
| <inertial> |
| <mass value="1.55" /> |
| <inertia ixx="0.011442" ixy="-0.000484" ixz="0.003405" iyy="0.01298" iyz="-0.001265" izz="0.003202"/> |
| <origin xyz="0.005 -0.001 0.016" rpy="-3.141592654 0 0"/> |
| </inertial> |
| <collision> |
| <origin xyz="0 0 0" rpy="-3.141592654 0 0"/> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-217_convex_hull.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="joint2" type="revolute"> |
| <parent link="link2"/> |
| <child link="link3"/> |
| <origin rpy="3.141592654 0 0" xyz="-0.046 0 -0.0674"/> |
| <axis xyz="0 1 0"/> |
| <limit effort="9.0" lower="0.0" upper="3.5" velocity="0.5"/> |
| </joint> |
|
|
| <link name="link3"> |
| <visual> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-250-212-214.stl"/> |
| </geometry> |
| <material name="blue"/> |
| </visual> |
| <inertial> |
| <mass value="1.14" /> |
| <origin xyz="0.022 -0.029 0.001" /> |
| <inertia ixx="0.003213" ixy="-0.001548" ixz="-0.000031" iyy="0.002327" iyz="0.000006" izz="0.00434"/> |
| </inertial> |
| <collision> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-250-212-214_convex_hull.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="joint3" type="revolute"> |
| <parent link="link3"/> |
| <child link="link4"/> |
| <origin rpy="0 0 0" xyz="-0.0052 0 -0.29055"/> |
| <axis xyz="0 1 0"/> |
| <limit effort="9.0" lower="0.0" upper="3.5" velocity="0.5"/> |
| </joint> |
|
|
| <link name="link4"> |
| <visual> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-268.stl"/> |
| </geometry> |
| <material name="green"/> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-268_convex_hull.stl"/> |
| </geometry> |
| <material name="green"/> |
| </collision> |
| <inertial> |
| <origin xyz="0.017 -0.026 -0.002" rpy="0.0 -0.0 0.0" /> |
| <mass value="1.14" /> |
| <inertia ixx="0.021232" ixy="0.00033" ixz="-0.003738" iyy="0.022252" iyz="-0.001278" izz="0.002054"/> |
| </inertial> |
| </link> |
|
|
| <joint name="joint4" type="continuous"> |
| <parent link="link4"/> |
| <child link="link5"/> |
| <origin rpy="3.141592654 0 0" xyz="0.0408 0 0.09695"/> |
| <axis xyz="0 0 1"/> |
| </joint> |
|
|
| <link name="link5"> |
| <visual> |
| <origin xyz="0 0 0" rpy="-3.141592654 0 0"/> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-214.stl"/> |
| </geometry> |
| <material name="blue"/> |
| </visual> |
| <inertial> |
| <mass value="1.03" /> |
| <origin xyz="0.020 -0.024 0.001" rpy="-3.141592654 0 0"/> |
| <inertia ixx="0.00243" ixy="-0.001144" ixz="-0.00004" iyy="0.002026" iyz="0.000011" izz="0.00333"/> |
| </inertial> |
| <collision> |
| <origin xyz="0 0 0" rpy="-3.141592654 0 0"/> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-214_convex_hull.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="joint5" type="revolute"> |
| <parent link="link5"/> |
| <child link="link6"/> |
| <origin rpy="3.141592654 0 0" xyz="-0.0408 0 -0.063"/> |
| <axis xyz="0 1 0"/> |
| <limit effort="9.0" lower="0.0" upper="3.5" velocity="0.5"/> |
| </joint> |
|
|
| <link name="link6"> |
| <visual> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-161.stl"/> |
| </geometry> |
| <material name="green"/> |
| </visual> |
| <inertial> |
| <origin xyz="0.0 0.003 -0.098" rpy="0.0 -0.0 0.0" /> |
| <mass value="0.333" /> |
| <inertia ixx="0.003709" ixy="-0.000002" ixz="-0.000004" iyy="0.003734" iyz="0.0" izz="0.000079" /> |
| </inertial> |
| <collision> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-161_convex_hull.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <joint name="joint6" type="continuous"> |
| <parent link="link6"/> |
| <child link="link7"/> |
| <origin rpy="0 3.14159 0" xyz="-0.0408 0 -0.14863"/> |
| <axis xyz="0 0 1"/> |
| </joint> |
|
|
| <link name="link7"> |
| <visual> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-180.stl"/> |
| </geometry> |
| <material name="blue"/> |
| </visual> |
| <inertial> |
| <origin xyz="0.0 0.003 -0.098" /> |
| <mass value="1.04" /> |
| <inertia ixx="0.022359" ixy="0.000001" ixz="-0.000019" iyy="0.022363" iyz="0.000015" izz="0.000936"/> |
| </inertial> |
| <collision> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-180_convex_hull.stl"/> |
| </geometry> |
| </collision> |
| </link> |
|
|
| <link name="force_torque_sensor"> |
| <visual> |
| <geometry> |
| <cylinder length="0.06" radius="0.04"/> |
| </geometry> |
| <material name="orange"/> |
| </visual> |
| <collision> |
| <geometry> |
| <cylinder length="0.06" radius="0.04"/> |
| </geometry> |
| <material name="orange"/> |
| </collision> |
| </link> |
|
|
| <joint name="FT_fixed_1" type="fixed"> |
| <origin rpy="0 0 1.57" xyz=" 0 0 -0.03"/> |
| <parent link="link7"/> |
| <child link="force_torque_sensor"/> |
| </joint> |
|
|
| <link name="end_effector_ball"> |
| <visual> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/end_effectors/contact_sphere.stl"/> |
| </geometry> |
| <material name="red"/> |
| </visual> |
| <collision> |
| <geometry> |
| <mesh filename="package://example-robot-data/robots/bravo7_description/meshes/end_effectors/contact_sphere_convex_hull.stl"/> |
| </geometry> |
| <material name="red"/> |
| </collision> |
| </link> |
|
|
| <joint name="bravo_EE_joint" type="fixed"> |
| <origin rpy="0 -1.57 0" xyz=" 0.045 -0.035 0.113"/> |
| <parent link="link7"/> |
| <child link="end_effector_ball"/> |
| </joint> |
|
|
| <link name="contact_point"/> |
|
|
| <joint name="contact_point_joint" type="fixed"> |
| <origin rpy="0 0 0" xyz="0 0 0.24"/> |
| <parent link="force_torque_sensor"/> |
| <child link="contact_point"/> |
| </joint> |
| </robot> |
|
|