76
76
<material>Gazebo/Grey</material>
77
77
<selfCollide>true</selfCollide>
79
<joint name="trunk_rotation" type="revolute">
79
<joint name="ShoulderJRotate" type="revolute">
80
80
<parent link="shadowarm_base"/>
81
81
<child link="shadowarm_trunk"/>
82
82
<origin rpy="0 0 0" xyz="0 0 0.01"/>
83
83
<axis xyz="0 0 1"/>
84
<limit effort="10" lower="-1.57079632679" upper="0.785398163397" velocity="1.0"/>
84
<limit effort="10" lower="-0.785398163397" upper="1.57079632679" velocity="1.0"/>
85
85
<dynamics damping="200.5"/>
87
87
<transmission name="trunk_rotation_transmission" type="pr2_mechanism_model/SimpleTransmission">
88
88
<actuator name="trunk_rotation"/>
89
<joint name="trunk_rotation"/>
89
<joint name="ShoulderJRotate"/>
90
90
<mechanicalReduction>1</mechanicalReduction>
91
91
<motorTorqueConstant>1</motorTorqueConstant>
92
92
<pulsesPerRevolution>90000</pulsesPerRevolution>
94
94
<link name="shadowarm_upperarm">
96
<origin rpy="0 0 0" xyz="0.1845 -0.067 0"/>
96
<origin rpy="0 0 0" xyz="0 -0.067 -0.1845"/>
98
98
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
101
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0.067 0"/>
101
<origin rpy="0 0 -1.57079632679" xyz="0 0.067 0"/>
102
102
<geometry name="shadowarm_upperarm_visual">
103
103
<mesh filename="package://sr_hand/model/meshes/arm/upper_arm.mesh" scale="0.001 0.001 0.001"/>
105
105
<material name="Grey"/>
108
<origin rpy="0 1.57079632679 0" xyz="0.1845 0 0"/>
108
<origin rpy="0 -3.14159265359 0" xyz="0 0 0.1845"/>
109
109
<geometry name="shadowarm_upperarm_collision">
110
110
<box size="0.03 0.03 0.369"/>
115
115
<material>Gazebo/Grey</material>
116
116
<selfCollide>true</selfCollide>
118
<joint name="shoulder_rotation" type="revolute">
118
<joint name="ShoulderJSwing" type="revolute">
119
119
<parent link="shadowarm_trunk"/>
120
120
<child link="shadowarm_upperarm"/>
121
<origin rpy="0 0 0" xyz="0 -0.134 0.5405"/>
121
<origin rpy="0 -3.14159265359 0" xyz="0 -0.134 0.5405"/>
123
123
<limit effort="10" lower="0" upper="1.57079632679" velocity="1.0"/>
124
124
<dynamics damping="50.5"/>
126
126
<transmission name="shoulder_rotation_transmission" type="pr2_mechanism_model/SimpleTransmission">
127
127
<actuator name="shoulder_rotation"/>
128
<joint name="shoulder_rotation"/>
128
<joint name="ShoulderJSwing"/>
129
129
<mechanicalReduction>1</mechanicalReduction>
130
130
<motorTorqueConstant>1</motorTorqueConstant>
131
131
<pulsesPerRevolution>90000</pulsesPerRevolution>
133
133
<link name="shadowarm_lowerarm">
135
<origin rpy="0 0 0" xyz="0.0655 0 -0.08"/>
135
<origin rpy="0 0 0" xyz="0.08 0 0.0655"/>
136
136
<mass value="1.7"/>
137
137
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
140
<origin rpy="3.14159265359 0.5 0" xyz="0.036 0 -0.03"/>
140
<origin rpy="3.14159265359 -1.07079632679 0" xyz="0.03 0 0.036"/>
141
141
<geometry name="shadowarm_lowerarm_visual">
142
142
<mesh filename="package://sr_hand/model/meshes/arm/elbow_flex.mesh" scale="0.001 0.001 0.001"/>
144
144
<material name="Grey"/>
147
<origin rpy="0 1.57079632679 0" xyz="0.0655 0 -0.08"/>
147
<origin rpy="0 0 0" xyz="0.08 0 0.0655"/>
148
148
<geometry name="shadowarm_lowerarm_collision">
149
149
<box size="0.03 0.03 0.131"/>
154
154
<material>Gazebo/Grey</material>
155
155
<selfCollide>true</selfCollide>
157
<joint name="elbow_abduction" type="revolute">
157
<joint name="ElbowJSwing" type="revolute">
158
158
<parent link="shadowarm_upperarm"/>
159
159
<child link="shadowarm_lowerarm"/>
160
<origin rpy="0 0 0" xyz="0.369 0 0"/>
160
<origin rpy="0 0 0" xyz="0 0 0.369"/>
161
161
<axis xyz="0 -1 0"/>
162
162
<limit effort="10" lower="0" upper="2.09439510239" velocity="1.0"/>
163
163
<dynamics damping="50.5"/>
165
165
<transmission name="elbow_abduction_transmission" type="pr2_mechanism_model/SimpleTransmission">
166
166
<actuator name="elbow_abduction"/>
167
<joint name="elbow_abduction"/>
167
<joint name="ElbowJSwing"/>
168
168
<mechanicalReduction>1</mechanicalReduction>
169
169
<motorTorqueConstant>1</motorTorqueConstant>
170
170
<pulsesPerRevolution>90000</pulsesPerRevolution>
176
176
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
179
<origin rpy="0 0 -1.57079632679" xyz="-0.04 0 0"/>
179
<origin rpy="1.57079632679 0 0" xyz="0 0 -0.04"/>
180
180
<geometry name="shadowarm_handsupport_visual">
181
181
<mesh filename="package://sr_hand/model/meshes/arm/elbow_rotate_muscle.mesh" scale="0.001 0.001 0.001"/>
183
183
<material name="LightGrey"/>
186
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
186
<origin rpy="0 0 0" xyz="0 0 0"/>
187
187
<geometry name="shadowarm_handsupport_collision">
188
188
<cylinder length="0.001" radius="0.06"/>
193
193
<material>Gazebo/Grey</material>
194
194
<selfCollide>true</selfCollide>
196
<joint name="forearm_rotation" type="revolute">
196
<joint name="ElbowJRotate" type="revolute">
197
197
<parent link="shadowarm_lowerarm"/>
198
198
<child link="shadowarm_handsupport_muscle"/>
199
<origin rpy="0 0 0" xyz="0.131 0 -0.08"/>
199
<origin rpy="0 0 0" xyz="0.08 0 0.131"/>
201
201
<limit effort="10" lower="-1.57079632679" upper="1.57079632679" velocity="1.0"/>
202
202
<dynamics damping="10.5"/>
204
204
<transmission name="forearm_rotation_transmission" type="pr2_mechanism_model/SimpleTransmission">
205
205
<actuator name="forearm_rotation"/>
206
<joint name="forearm_rotation"/>
206
<joint name="ElbowJRotate"/>
207
207
<mechanicalReduction>1</mechanicalReduction>
208
208
<motorTorqueConstant>1</motorTorqueConstant>
209
209
<pulsesPerRevolution>90000</pulsesPerRevolution>