<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_main">
|
|
<xacro:property name="M_PI" value="3.1415926535897931" />
|
|
<xacro:property name="joint_damping" value="21.75"/>
|
|
<xacro:property name="joint_friction" value="10.48"/>
|
|
<xacro:property name="joint_spring_stiffness" value="0"/>
|
|
<xacro:property name="joint_spring_reference" value="0"/>
|
|
|
|
<link
|
|
name="base_link">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.087526 -0.001626 0.081009"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="17.384389" />
|
|
<inertia
|
|
ixx="0.160002"
|
|
ixy="0.006758"
|
|
ixz="0.004621"
|
|
iyy="0.138068"
|
|
iyz="0.002208"
|
|
izz="0.228992" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/base_link.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/base_link.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<link
|
|
name="link_right_wheel">
|
|
<inertial>
|
|
<origin
|
|
xyz="0 0 0.02765"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.20773" />
|
|
<inertia
|
|
ixx="5.4E-05"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="5.4E-05"
|
|
iyz="0"
|
|
izz="5.1E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_right_wheel.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_right_wheel.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_right_wheel"
|
|
type="continuous">
|
|
<origin
|
|
xyz="0 -0.17035 0.0508"
|
|
rpy="-1.5708 1.2717E-16 4.8006E-17" />
|
|
<parent
|
|
link="base_link" />
|
|
<child
|
|
link="link_right_wheel" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<dynamics damping="${joint_damping}" friction="${joint_friction}" spring_reference="${joint_spring_reference}" spring_stiffness="${joint_spring_stiffness}"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_left_wheel">
|
|
<inertial>
|
|
<origin
|
|
xyz="0 0 -0.02765"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.20773" />
|
|
<inertia
|
|
ixx="5.4E-05"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="5.4E-05"
|
|
iyz="0"
|
|
izz="5.1E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_left_wheel.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_left_wheel.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_left_wheel"
|
|
type="continuous">
|
|
<origin
|
|
xyz="0 0.17035 0.0508"
|
|
rpy="-1.5708 2.6317E-16 -8.2057E-19" />
|
|
<parent
|
|
link="base_link" />
|
|
<child
|
|
link="link_left_wheel" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<dynamics damping="${joint_damping}" friction="${joint_friction}" spring_reference="${joint_spring_reference}" spring_stiffness="${joint_spring_stiffness}"/>
|
|
</joint>
|
|
|
|
<link name="caster_link">
|
|
<collision>
|
|
<geometry>
|
|
<sphere radius="0.032"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<surface>
|
|
<friction>
|
|
<ode>
|
|
<mu>0</mu>
|
|
<mu2>0</mu2>
|
|
<slip1>1.0</slip1>
|
|
<slip2>1.0</slip2>
|
|
</ode>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/omni_wheel_m.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<inertial>
|
|
<mass value="0.01" />
|
|
<origin xyz="0 0 0" />
|
|
<inertia
|
|
ixx="0.001"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="0.001"
|
|
iyz="0"
|
|
izz="0.001" />
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="caster_joint" type="fixed">
|
|
<parent link="base_link"/>
|
|
<child link="caster_link"/>
|
|
<origin xyz="-0.245 0.0 0.032" rpy="${-M_PI/2} 0 0"/>
|
|
<axis xyz="0 0 1" />
|
|
</joint>
|
|
|
|
<link
|
|
name="link_mast">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.000337 0.722201 0.002652"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="1.764017" />
|
|
<inertia
|
|
ixx="0.291286"
|
|
ixy="0.004149"
|
|
ixz="-0.000174"
|
|
iyy="0.001226"
|
|
iyz="0.000354"
|
|
izz="0.291429" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_mast.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_mast.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_mast"
|
|
type="fixed">
|
|
<origin
|
|
xyz="-0.067 0.135 0.0284"
|
|
rpy="1.5708 0 4.8006E-17" />
|
|
<parent
|
|
link="base_link" />
|
|
<child
|
|
link="link_mast" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
<link
|
|
name="link_lift">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.020369 0.03438 0.02236"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="1.987167" />
|
|
<inertia
|
|
ixx="0.006518"
|
|
ixy="-0.001539"
|
|
ixz="0.000371"
|
|
iyy="0.004464"
|
|
iyz="0.000392"
|
|
izz="0.008092" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_lift.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_lift.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_lift"
|
|
type="prismatic">
|
|
<origin
|
|
xyz="-0.037385 0.1666 0"
|
|
rpy="-1.5708 1.5708 0" />
|
|
<parent
|
|
link="link_mast" />
|
|
<child
|
|
link="link_lift" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- for now: hand copied range_m: from lift: from ~/repos/stretch_fleet/stretch-re1-1001/stretch_re1_factory_params.yaml -->
|
|
<!--<limit effort="100" lower="0.0" upper="1.095" velocity="1.0"/>-->
|
|
<!-- copied value did not reach the top of mesh model with GUI sliders and RViz -->
|
|
<limit effort="100" lower="0.0" upper="1.1" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_arm_l4">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.000168 -0.000254 -0.125235"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.235626" />
|
|
<inertia
|
|
ixx="0.001518"
|
|
ixy="-1E-06"
|
|
ixz="3E-06"
|
|
iyy="0.001519"
|
|
iyz="3E-06"
|
|
izz="0.000176" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l4.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l4.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_arm_l4"
|
|
type="fixed">
|
|
<origin
|
|
xyz="-0.2547 0 0"
|
|
rpy="1.5708 2.4721E-15 -1.5708" />
|
|
<parent
|
|
link="link_lift" />
|
|
<child
|
|
link="link_arm_l4" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
<link
|
|
name="link_arm_l3">
|
|
<inertial>
|
|
<origin
|
|
xyz="-1E-06 -0.000146 -0.11908"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.146817" />
|
|
<inertia
|
|
ixx="0.001081"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="0.001081"
|
|
iyz="-1E-06"
|
|
izz="7.7E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l3.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l3.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_arm_l3"
|
|
type="prismatic">
|
|
<origin
|
|
xyz="0 0 0.013"
|
|
rpy="7.68831233799385E-30 2.36716479416092E-30 2.29652732251143E-17" />
|
|
<parent
|
|
link="link_arm_l4" />
|
|
<child
|
|
link="link_arm_l3" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- 0.13 = 0.52/4-->
|
|
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_arm_l2">
|
|
<inertial>
|
|
<origin
|
|
xyz="0 -7.1E-05 -0.115635"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.130565" />
|
|
<inertia
|
|
ixx="0.000943"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="0.000943"
|
|
iyz="0"
|
|
izz="5.7E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l2.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l2.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_arm_l2"
|
|
type="prismatic">
|
|
<origin
|
|
xyz="0 0 0.013"
|
|
rpy="0 1.57655765344625E-30 -1.66533453693773E-16" />
|
|
<parent
|
|
link="link_arm_l3" />
|
|
<child
|
|
link="link_arm_l2" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- 0.13 = 0.52/4-->
|
|
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_arm_l1">
|
|
<inertial>
|
|
<origin
|
|
xyz="-1E-06 -0.000121 -0.113457"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.113658" />
|
|
<inertia
|
|
ixx="0.0008"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="0.0008"
|
|
iyz="0"
|
|
izz="4E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l1.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.79216 0.81961 0.93333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l1.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_arm_l1"
|
|
type="prismatic">
|
|
<origin
|
|
xyz="0 0 0.0129999999999981"
|
|
rpy="-7.63746778746202E-30 -7.88860905221012E-31 1.11022302462516E-16" />
|
|
<parent
|
|
link="link_arm_l2" />
|
|
<child
|
|
link="link_arm_l1" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- 0.13 = 0.52/4-->
|
|
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_arm_l0">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.033681 -0.000847 -0.031723"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.427734" />
|
|
<inertia
|
|
ixx="0.001689"
|
|
ixy="-2.8E-05"
|
|
ixz="0.000483"
|
|
iyy="0.002107"
|
|
iyz="-1.1E-05"
|
|
izz="0.000571" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l0.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_arm_l0.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_arm_l0"
|
|
type="prismatic">
|
|
<origin
|
|
xyz="0 0 -0.0137499999991968"
|
|
rpy="7.63746778746202E-30 -3.80121128864402E-15 2.62707547767438E-15" />
|
|
<parent
|
|
link="link_arm_l1" />
|
|
<child
|
|
link="link_arm_l0" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- 0.13 = 0.52/4-->
|
|
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_wrist_yaw">
|
|
<inertial>
|
|
<origin
|
|
xyz="0 -3.9E-05 -0.016495"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.054422" />
|
|
<inertia
|
|
ixx="9E-06"
|
|
ixy="0"
|
|
ixz="0"
|
|
iyy="9E-06"
|
|
iyz="0"
|
|
izz="7E-06" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_wrist_yaw.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.898039215686275 0.917647058823529 0.929411764705882 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_wrist_yaw.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_wrist_yaw"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0.0830000000000654 -0.0307500000000129 0"
|
|
rpy="1.5708 4.2595E-14 2.6415E-15"/>
|
|
<parent
|
|
link="link_arm_l0" />
|
|
<child
|
|
link="link_wrist_yaw" />
|
|
<axis
|
|
xyz="0 0 -1" />
|
|
<!--
|
|
stowed to front ~225 deg: 3.15159 x 1.25 = 3.9395
|
|
using 4.0
|
|
stowed to back ~100 deg: 100 / 180 x 3.14159 = 1.7453
|
|
using -1.75
|
|
-->
|
|
<limit effort="100" lower="-1.75" upper="4.0" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_head">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.047462 0.04451 0.016376"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.681871" />
|
|
<inertia
|
|
ixx="0.001023"
|
|
ixy="0.000641"
|
|
ixz="6.6E-05"
|
|
iyy="0.002097"
|
|
iyz="6.5E-05"
|
|
izz="0.00281" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_head.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_head.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_head"
|
|
type="fixed">
|
|
<origin
|
|
xyz="0 1.33 0"
|
|
rpy="1.5707963267949 -1.5707963267949 3.1416" />
|
|
<parent
|
|
link="link_mast" />
|
|
<child
|
|
link="link_head" />
|
|
<axis
|
|
xyz="0 0 0" />
|
|
</joint>
|
|
|
|
<link
|
|
name="link_head_pan">
|
|
<inertial>
|
|
<origin
|
|
xyz="-0.000422 0.013934 -0.0161"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.062462" />
|
|
<inertia
|
|
ixx="4.1E-05"
|
|
ixy="-1E-06"
|
|
ixz="1E-06"
|
|
iyy="3.2E-05"
|
|
iyz="-1.5E-05"
|
|
izz="2.2E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_head_pan.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_head_pan.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_head_pan"
|
|
type="revolute">
|
|
<origin
|
|
xyz="0.135 0.0731000000000001 -0.00319621125547975"
|
|
rpy="0 0 1.5707963267949" />
|
|
<parent
|
|
link="link_head" />
|
|
<child
|
|
link="link_head_pan" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- unconstrained range for now -->
|
|
<limit effort="100" lower="-3.9" upper="1.5" velocity="1.0"/>
|
|
</joint>
|
|
|
|
<link
|
|
name="link_head_tilt">
|
|
<inertial>
|
|
<origin
|
|
xyz="0.003907 -0.02418 0.030154"
|
|
rpy="0 0 0" />
|
|
<mass
|
|
value="0.283548" />
|
|
<inertia
|
|
ixx="0.000316"
|
|
ixy="-6E-06"
|
|
ixz="1E-06"
|
|
iyy="0.000143"
|
|
iyz="-2E-06"
|
|
izz="0.00031" />
|
|
</inertial>
|
|
<visual>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_head_tilt.STL" />
|
|
</geometry>
|
|
<material
|
|
name="">
|
|
<color
|
|
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin
|
|
xyz="0 0 0"
|
|
rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh
|
|
filename="package://stretch_description/meshes/link_head_tilt.STL" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint
|
|
name="joint_head_tilt"
|
|
type="revolute">
|
|
<origin
|
|
xyz="-0.00130000001785262 0.0277624999926072 -0.0533107920897029"
|
|
rpy="1.5707963267949 3.36459255518345E-15 -8.42914893687103E-17" />
|
|
<parent
|
|
link="link_head_pan" />
|
|
<child
|
|
link="link_head_tilt" />
|
|
<axis
|
|
xyz="0 0 1" />
|
|
<!-- unconstrained range for now -->
|
|
<limit effort="100" lower="-1.53" upper="0.79" velocity="1.0"/>
|
|
</joint>
|
|
|
|
</robot>
|