1
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
3
<include filename="$(find sr_hand)/model/arm_urdf/hand_support/shadowarm_handsupport_muscle.transmission.xacro" />
5
<xacro:macro name="shadowarm_handsupport_muscle" params="parent">
7
<link name="shadowarm_handsupport_muscle">
9
<origin xyz="0 0 0" rpy="0 0 0" />
11
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0" />
14
<origin xyz="0 0 -0.04" rpy="${M_PI/2} 0 0"/>
15
<geometry name="shadowarm_handsupport_visual">
16
<mesh filename="package://sr_hand/model/meshes/arm/elbow_rotate_muscle.mesh" scale="0.001 0.001 0.001" />
18
<material name="LightGrey" />
21
<origin xyz="0 0 0" rpy="0 0 0"/>
22
<geometry name="shadowarm_handsupport_collision">
23
<cylinder radius="0.06" length="0.001"/>
27
<gazebo reference="shadowarm_handsupport_muscle">
28
<material>Gazebo/Grey</material>
29
<selfCollide>true</selfCollide>
32
<joint name="ElbowJRotate" type="revolute">
33
<parent link="${parent}"/>
34
<child link="shadowarm_handsupport_muscle"/>
35
<origin xyz="0.08 0 0.131" rpy="0 0 0" />
37
<limit lower="-${M_PI/2}" upper="${M_PI/2}"
38
effort="10" velocity="1.0"/>
39
<dynamics damping="10.5"/>
42
<xacro:shadowarm_handsupport_muscle_transmission />