unitree_ros/robots/b2w_description/urdf/b2w_description.urdf

1248 lines
26 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="b2w_description">
<link
name="base_link">
<inertial>
<origin
xyz="0.000458 0.005261 0.000665"
rpy="0 0 0" />
<mass
value="35.606" />
<inertia
ixx="0.27466"
ixy="-0.000622"
ixz="0.00315"
iyy="1.0618"
iyz="-0.00139"
izz="1.1825" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/base_link.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<box size="0.5 0.28 0.15" />
</geometry>
</collision>
</link>
<link
name="lidar_link">
<inertial>
<origin
xyz="0.34218 0 0.17851"
rpy="0 0 0" />
<mass
value="4.19E-15" />
<inertia
ixx="1.68E-27"
ixy="-3.2E-45"
ixz="7.68E-44"
iyy="1.68E-27"
iyz="-9.26E-47"
izz="1.68E-27" />
</inertial>
<collision>
<origin
xyz="0 0 -0.02"
rpy="0 0 0" />
<geometry>
<cylinder length="0.16" radius="0.076" />
<!-- <mesh
filename="package://b2_description/meshes/lidar_link.STL" /> -->
</geometry>
</collision>
</link>
<joint
name="joint_lidar"
type="fixed">
<origin
xyz="0.34218 0 0.17851"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="lidar_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="f_dc_link">
<inertial>
<origin
xyz="3.47E-18 0 5.55E-17"
rpy="0 0 0" />
<mass
value="4.19E-15" />
<inertia
ixx="1.68E-27"
ixy="-9.81E-45"
ixz="-2.54E-44"
iyy="1.68E-27"
iyz="0"
izz="1.68E-27" />
</inertial>
</link>
<joint
name="joint_f_dc"
type="fixed">
<origin
xyz="0.42161 0.025 0.061851"
rpy="-2.3562 0 -1.5708" />
<parent
link="base_link" />
<child
link="f_dc_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="r_dc_link">
<inertial>
<origin
xyz="-7.46E-16 -3.33E-16 -1.11E-15"
rpy="0 0 0" />
<mass
value="4.19E-15" />
<inertia
ixx="1.68E-27"
ixy="-4.31E-44"
ixz="2.48E-45"
iyy="1.68E-27"
iyz="0"
izz="1.68E-27" />
</inertial>
</link>
<joint
name="joint_r_dc"
type="fixed">
<origin
xyz="-0.42244 -0.025 0.038026"
rpy="-2.3562 0 1.5708" />
<parent
link="base_link" />
<child
link="r_dc_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="imu_link">
<inertial>
<origin
xyz="-2.02E-17 1.73E-17 -1.39E-17"
rpy="0 0 0" />
<mass
value="4.19E-15" />
<inertia
ixx="1.68E-27"
ixy="1.84E-44"
ixz="-7.35E-44"
iyy="1.68E-27"
iyz="-3.67E-44"
izz="1.68E-27" />
</inertial>
</link>
<joint
name="joint_imu"
type="fixed">
<origin
xyz="0 -0.02341 0.04927"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="imu_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="head_Link">
<inertial>
<origin
xyz="0.33989 -0.000168 0.12029"
rpy="0 0 0" />
<mass
value="3.366" />
<inertia
ixx="0.026455"
ixy="3.15E-05"
ixz="0.00166"
iyy="0.029221"
iyz="-3.27E-05"
izz="0.010918" />
</inertial>
<collision>
<origin
xyz="0.41 0 0.005"
rpy="0 0 0" />
<geometry>
<box size="0.04 0.12 0.14" />
</geometry>
</collision>
</link>
<joint
name="joint_head"
type="fixed">
<origin
xyz="0 0 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="head_Link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="tail_link">
<inertial>
<origin
xyz="-0.37448 0.000488 0.006495"
rpy="0 0 0" />
<mass
value="0.777" />
<inertia
ixx="0.0028118"
ixy="1.95E-05"
ixz="-7.87E-06"
iyy="0.0047506"
iyz="-1.57E-05"
izz="0.0029154" />
</inertial>
<collision>
<origin
xyz="-0.405 0 0.005"
rpy="0 0 0" />
<geometry>
<box size="0.025 0.12 0.14" />
</geometry>
</collision>
</link>
<joint
name="joint_tail"
type="fixed">
<origin
xyz="0 0 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="tail_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="FL_hip">
<inertial>
<origin
xyz="-0.009305 -0.010228 0.000264"
rpy="0 0 0" />
<mass
value="2.256" />
<inertia
ixx="0.0026431"
ixy="0.00019234"
ixz="-6.76E-06"
iyy="0.0046728"
iyz="-7.16E-06"
izz="0.0034208" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FL_hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0.12 0"
rpy="1.5707963267948966 0 0" />
<geometry>
<cylinder length="0.05" radius="0.07" />
</geometry>
</collision>
</link>
<joint
name="FL_hip_joint"
type="revolute">
<origin
xyz="0.3285 0.072 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="FL_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-0.87"
upper="0.87"
effort="200"
velocity="23" />
</joint>
<link
name="FL_thigh">
<inertial>
<origin
xyz="-0.004346 -0.035797 -0.044921"
rpy="0 0 0" />
<mass
value="3.591" />
<inertia
ixx="0.041718"
ixy="0.00055623"
ixz="-0.0022768"
iyy="0.041071"
iyz="0.005796"
izz="0.0065677" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FL_thigh.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="-0.025 0 -0.16"
rpy="0 1.57 0" />
<geometry>
<box size="0.32 0.0445 0.054" />
</geometry>
</collision>
</link>
<joint
name="FL_thigh_joint"
type="revolute">
<origin
xyz="0 0.11973 0"
rpy="0 0 0" />
<parent
link="FL_hip" />
<child
link="FL_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-0.94"
upper="4.69"
effort="200"
velocity="23" />
</joint>
<link
name="FL_calf">
<inertial>
<origin
xyz="0.006095 0.012046 -0.29122"
rpy="0 0 0" />
<mass
value="2.053" />
<inertia
ixx="0.028133"
ixy="0.00016307"
ixz="-0.0010034"
iyy="0.029251"
iyz="0.0014765"
izz="0.0028379" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FL_calf.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FL_calf.dae" />
</geometry>
</collision>
</link>
<joint
name="FL_calf_joint"
type="revolute">
<origin
xyz="0 -8.8203E-05 -0.35"
rpy="0 0 0" />
<parent
link="FL_thigh" />
<child
link="FL_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.82"
upper="-0.43"
effort="320"
velocity="14" />
</joint>
<link
name="FL_foot">
<inertial>
<origin
xyz="0 0.051576 0"
rpy="0 0 0" />
<mass
value="0.918" />
<inertia
ixx="0.0032475"
ixy="0"
ixz="0"
iyy="0.0061101"
iyz="0"
izz="0.003235" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FL_foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FL_foot.dae" />
</geometry>
</collision>
</link>
<joint
name="FL_foot_joint"
type="continuous">
<origin
xyz="0 0 -0.35"
rpy="0 0 0" />
<parent
link="FL_calf" />
<child
link="FL_foot" />
<axis
xyz="0 1 0" />
<limit
effort="20"
velocity="50" />
</joint>
<link
name="FR_hip">
<inertial>
<origin
xyz="-0.009305 0.010228 0.000264"
rpy="0 0 0" />
<mass
value="2.256" />
<inertia
ixx="0.0026431"
ixy="-0.00019234"
ixz="-6.76E-06"
iyy="0.0046728"
iyz="7.16E-06"
izz="0.0034208" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FR_hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 -0.12 0"
rpy="1.5707963267948966 0 0" />
<geometry>
<cylinder length="0.05" radius="0.07" />
</geometry>
</collision>
</link>
<joint
name="FR_hip_joint"
type="revolute">
<origin
xyz="0.3285 -0.072 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="FR_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-0.87"
upper="0.87"
effort="200"
velocity="23" />
</joint>
<link
name="FR_thigh">
<inertial>
<origin
xyz="-0.004346 0.035797 -0.044921"
rpy="0 0 0" />
<mass
value="3.591" />
<inertia
ixx="0.041718"
ixy="-0.00055623"
ixz="-0.0022768"
iyy="0.041071"
iyz="-0.005796"
izz="0.0065677" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FR_thigh.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.57 0" xyz="-0.03 0 -0.2"/>
<geometry>
<box size="0.25 0.028 0.04"/>
</geometry>
</collision>
</link>
<joint
name="FR_thigh_joint"
type="revolute">
<origin
xyz="0 -0.11973 0"
rpy="0 0 0" />
<parent
link="FR_hip" />
<child
link="FR_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-0.94"
upper="4.69"
effort="200"
velocity="23" />
</joint>
<link
name="FR_calf">
<inertial>
<origin
xyz="0.006095 -0.012046 -0.29122"
rpy="0 0 0" />
<mass
value="2.053" />
<inertia
ixx="0.028133"
ixy="-0.00016307"
ixz="-0.0010034"
iyy="0.029251"
iyz="-0.0014765"
izz="0.0028379" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FR_calf.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FR_calf.dae" />
</geometry>
</collision>
</link>
<joint
name="FR_calf_joint"
type="revolute">
<origin
xyz="0 8.8205E-05 -0.35"
rpy="0 0 0" />
<parent
link="FR_thigh" />
<child
link="FR_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.82"
upper="-0.43"
effort="320"
velocity="14" />
</joint>
<link
name="FR_foot">
<inertial>
<origin
xyz="0 -0.051576 0"
rpy="0 0 0" />
<mass
value="0.918" />
<inertia
ixx="0.0032475"
ixy="0"
ixz="0"
iyy="0.0061101"
iyz="0"
izz="0.003235" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FR_foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/FR_foot.dae" />
</geometry>
</collision>
</link>
<joint
name="FR_foot_joint"
type="continuous">
<origin
xyz="0 -0.001 -0.35"
rpy="0 0 0" />
<parent
link="FR_calf" />
<child
link="FR_foot" />
<axis
xyz="0 1 0" />
<limit
effort="20"
velocity="50" />
</joint>
<link
name="RL_hip">
<inertial>
<origin
xyz="0.009305 -0.010228 0.000264"
rpy="0 0 0" />
<mass
value="2.256" />
<inertia
ixx="0.0026431"
ixy="-0.00019234"
ixz="6.76E-06"
iyy="0.0046728"
iyz="-7.16E-06"
izz="0.0034208" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RL_hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0.12 0"
rpy="1.5707963267948966 0 0" />
<geometry>
<cylinder length="0.05" radius="0.07" />
</geometry>
</collision>
</link>
<joint
name="RL_hip_joint"
type="revolute">
<origin
xyz="-0.3285 0.072 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="RL_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-0.87"
upper="0.87"
effort="200"
velocity="23" />
</joint>
<link
name="RL_thigh">
<inertial>
<origin
xyz="-0.004346 -0.035797 -0.044921"
rpy="0 0 0" />
<mass
value="3.591" />
<inertia
ixx="0.041718"
ixy="0.00055623"
ixz="-0.0022768"
iyy="0.041071"
iyz="0.005796"
izz="0.0065677" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RL_thigh.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.57 0" xyz="-0.03 0 -0.2"/>
<geometry>
<box size="0.25 0.028 0.04"/>
</geometry>
</collision>
</link>
<joint
name="RL_thigh_joint"
type="revolute">
<origin
xyz="0 0.11973 0"
rpy="0 0 0" />
<parent
link="RL_hip" />
<child
link="RL_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-0.94"
upper="4.69"
effort="200"
velocity="23" />
</joint>
<link
name="RL_calf">
<inertial>
<origin
xyz="0.006095 0.012046 -0.29122"
rpy="0 0 0" />
<mass
value="2.053" />
<inertia
ixx="0.028133"
ixy="0.00016307"
ixz="-0.0010034"
iyy="0.029251"
iyz="0.0014765"
izz="0.0028379" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RL_calf.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RL_calf.dae" />
</geometry>
</collision>
</link>
<joint
name="RL_calf_joint"
type="revolute">
<origin
xyz="0 -8.8205E-05 -0.35"
rpy="0 0 0" />
<parent
link="RL_thigh" />
<child
link="RL_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.82"
upper="-0.43"
effort="320"
velocity="14" />
</joint>
<link
name="RL_foot">
<inertial>
<origin
xyz="0 0.051576 0"
rpy="0 0 0" />
<mass
value="0.918" />
<inertia
ixx="0.0032475"
ixy="0"
ixz="0"
iyy="0.0061101"
iyz="0"
izz="0.003235" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RL_foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RL_foot.dae" />
</geometry>
</collision>
</link>
<joint
name="RL_foot_joint"
type="continuous">
<origin
xyz="0 0 -0.35"
rpy="0 0 0" />
<parent
link="RL_calf" />
<child
link="RL_foot" />
<axis
xyz="0 1 0" />
<limit
effort="20"
velocity="50" />
</joint>
<link
name="RR_hip">
<inertial>
<origin
xyz="0.009305 -0.010228 0.000264"
rpy="0 0 0" />
<mass
value="2.256" />
<inertia
ixx="0.0026431"
ixy="0.00019234"
ixz="6.76E-06"
iyy="0.0046728"
iyz="7.16E-06"
izz="0.0034208" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RR_hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 -0.12 0"
rpy="1.5707963267948966 0 0" />
<geometry>
<cylinder length="0.05" radius="0.07" />
</geometry>
</collision>
</link>
<joint
name="RR_hip_joint"
type="revolute">
<origin
xyz="-0.3285 -0.072 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="RR_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-0.87"
upper="0.87"
effort="200"
velocity="23" />
</joint>
<link
name="RR_thigh">
<inertial>
<origin
xyz="-0.004346 0.035797 -0.044921"
rpy="0 0 0" />
<mass
value="3.591" />
<inertia
ixx="0.041718"
ixy="-0.00055623"
ixz="-0.0022768"
iyy="0.041071"
iyz="-0.005796"
izz="0.0065677" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RR_thigh.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin rpy="0 1.57 0" xyz="-0.03 0 -0.2"/>
<geometry>
<box size="0.25 0.028 0.04"/>
</geometry>
</collision>
</link>
<joint
name="RR_thigh_joint"
type="revolute">
<origin
xyz="0 -0.11973 0"
rpy="0 0 0" />
<parent
link="RR_hip" />
<child
link="RR_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-0.94"
upper="4.69"
effort="200"
velocity="23" />
</joint>
<link
name="RR_calf">
<inertial>
<origin
xyz="0.006095 -0.012046 -0.29122"
rpy="0 0 0" />
<mass
value="2.053" />
<inertia
ixx="0.028133"
ixy="-0.00016307"
ixz="-0.0010034"
iyy="0.029251"
iyz="-0.0014765"
izz="0.0028379" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RR_calf.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RR_calf.dae" />
</geometry>
</collision>
</link>
<joint
name="RR_calf_joint"
type="revolute">
<origin
xyz="0 8.8205E-05 -0.35"
rpy="0 0 0" />
<parent
link="RR_thigh" />
<child
link="RR_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.82"
upper="-0.43"
effort="320"
velocity="14" />
</joint>
<link
name="RR_foot">
<inertial>
<origin
xyz="0 -0.051576 0"
rpy="0 0 0" />
<mass
value="0.918" />
<inertia
ixx="0.0032475"
ixy="0"
ixz="0"
iyy="0.0061101"
iyz="0"
izz="0.003235" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RR_foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://b2w_description/meshes/RR_foot.dae" />
</geometry>
</collision>
</link>
<joint
name="RR_foot_joint"
type="continuous">
<origin
xyz="0 -0.001 -0.35"
rpy="0 0 0" />
<parent
link="RR_calf" />
<child
link="RR_foot" />
<axis
xyz="0 1 0" />
<limit
effort="20"
velocity="50" />
</joint>
<link
name="f_oc_link">
<inertial>
<origin
xyz="-3.39E-15 1.46E-16 -6.11E-16"
rpy="0 0 0" />
<mass
value="4.19E-15" />
<inertia
ixx="1.68E-27"
ixy="-3.89E-44"
ixz="5.04E-44"
iyy="1.68E-27"
iyz="2.81E-45"
izz="1.68E-27" />
</inertial>
</link>
<joint
name="f_oc_link"
type="fixed">
<origin
xyz="0.3993 0 -0.01576"
rpy="-1.5708 0 -1.5708" />
<parent
link="base_link" />
<child
link="f_oc_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="logo_link">
<inertial>
<origin
xyz="0 -2.3E-23 0"
rpy="0 0 0" />
<mass
value="4.19E-15" />
<inertia
ixx="1.68E-27"
ixy="0"
ixz="0"
iyy="1.68E-27"
iyz="0"
izz="1.68E-27" />
</inertial>
</link>
<joint
name="joint_logo"
type="fixed">
<origin
xyz="0 0 0"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="logo_link" />
<axis
xyz="0 0 0" />
</joint>
<link
name="r_oc_ink">
<inertial>
<origin
xyz="-0.39143 1.52E-07 -0.011961"
rpy="0 0 0" />
<mass
value="4.19E-12" />
<inertia
ixx="1.68E-22"
ixy="9.03E-39"
ixz="0"
iyy="1.68E-22"
iyz="-1.2E-38"
izz="1.68E-22" />
</inertial>
</link>
<joint
name="joint_r_oc"
type="fixed">
<origin
xyz="-0.39143 0 -0.026131"
rpy="-1.5708 0 1.5708" />
<parent
link="base_link" />
<child
link="r_oc_ink" />
<axis
xyz="0 0 0" />
</joint>
</robot>