Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions python/example_robot_data/human.py
Original file line number Diff line number Diff line change
Expand Up @@ -911,7 +911,7 @@ def get_dict_meshes_scale(
"left_lowerleg_1",
"left_foot_0",
"middle_abdomen_0",
"middle_abdomen_1",
"middle_thorax_0",
"middle_head_0",
"middle_head_1",
"left_upperarm_0",
Expand Down Expand Up @@ -1020,7 +1020,7 @@ def get_dict_meshes_scale(
)
scales.append(scale)
elif (
name == "middle_abdomen_1"
name == "middle_thorax_0"
): # torso mesh size is : X = 36.991m, Y = 35m, Z = 40.029m
scale = np.round(
np.array(
Expand Down
42 changes: 21 additions & 21 deletions robots/human_description/robots/human.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,10 @@
<link name="left_upperleg_virtual_2"/>
<joint name="left_hip_Y" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="0 1 0" />
<axis xyz="0 -1 0" />
<parent link="left_upperleg_virtual_2" />
<child link="left_upperleg" />
<limit effort="60" velocity="12.0" lower="-1.047196667" upper="1.570795" />
<limit effort="60" velocity="12.0" lower="-1.570795" upper="1.047196667" />
</joint>
<link name="left_upperleg">
<inertial>
Expand Down Expand Up @@ -122,7 +122,7 @@
<axis xyz="0 0 -1" />
<parent link="middle_pelvis" />
<child link="middle_abdomen_virtual" />
<limit effort="190" velocity="5.2" lower="-3.14159" upper="0.785398" />
<limit effort="190" velocity="5.2" lower="-0.785398" upper="3.14159" />
</joint>
<link name="middle_abdomen_virtual" />
<joint name="middle_lumbar_X" type="revolute">
Expand All @@ -146,21 +146,13 @@
</geometry>
<material name="body_color"/>
</visual>
<visual>
<origin xyz="-0.0 -0.1 0.0" rpy="0 -0 0" />
<geometry>
<!--<box size="0.15 0.356643 0.329994" />-->
<mesh filename="package://example-robot-data/robots/human_description/meshes/torso_mesh.STL" scale="0.007 0.007 0.007"/>
</geometry>
<material name="body_color"/>
</visual>
</link>
<joint name="middle_thoracic_Z" type="revolute">
<origin xyz="0 0.223 0" rpy="0 -0 0" />
<axis xyz="0 0 -1" />
<parent link="middle_abdomen" />
<child link="middle_thorax_virtual" />
<limit effort="190" velocity="5.2" lower="-1.0472" upper="0.392699" />
<limit effort="190" velocity="5.2" lower="-0.392699" upper="1.0472" />
</joint>
<link name="middle_thorax_virtual" />
<joint name="middle_thoracic_X" type="revolute">
Expand All @@ -184,6 +176,14 @@
<origin xyz="-0.009 0.127 -0.001" rpy="0 -0 0" />
<inertia ixx="0.05463" ixy="0.02428" ixz="-0.0003" iyy="0.04683" iyz="-0.0012" izz="0.05875" />
</inertial>
<visual>
<origin xyz="-0.0 -0.32 0.0" rpy="0 -0 0" />
<geometry>
<!--<box size="0.15 0.356643 0.329994" />-->
<mesh filename="package://example-robot-data/robots/human_description/meshes/torso_mesh.STL" scale="0.007 0.007 0.007"/>
</geometry>
<material name="body_color"/>
</visual>
</link>
<joint name="middle_cervical_Z" type="revolute">
<origin xyz="0 0.25 0" rpy="0 -0 0" />
Expand Down Expand Up @@ -234,7 +234,7 @@
<axis xyz="1 0 0" />
<parent link="middle_thorax" />
<child link="left_clavicle" />
<limit effort="100" velocity="14.0" lower="-1.0472" upper="0.349066" />
<limit effort="100" velocity="14.0" lower="-0.349066" upper="1.0472" />
</joint>
<link name="left_clavicle">
<inertial>
Expand All @@ -261,7 +261,7 @@
<link name="left_upperarm_virtual_2" />
<joint name="left_shoulder_Y" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="0 1 0" />
<axis xyz="0 -1 0" />
<parent link="left_upperarm_virtual_2" />
<child link="left_upperarm" />
<limit effort="52" velocity="6.0" lower="-1.5708" upper="3.14159" />
Expand Down Expand Up @@ -297,10 +297,10 @@
<link name="left_lowerarm_virtual"/>
<joint name="left_elbow_Y" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="0 1 0" />
<axis xyz="0 -1 0" />
<parent link="left_lowerarm_virtual" />
<child link="left_lowerarm" />
<limit effort="15" velocity="6.0" lower="-3.14159" upper="0.349066" />
<limit effort="15" velocity="6.0" lower="-0.349066" upper="3.14159" />
</joint>
<link name="left_lowerarm">
<inertial>
Expand Down Expand Up @@ -333,7 +333,7 @@
<link name="left_hand_virtual" />
<joint name="left_wrist_X" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="-1 0 0" />
<axis xyz="1 0 0" />
<parent link="left_hand_virtual" />
<child link="left_hand" />
<limit effort="100" velocity="6.0" lower="-0.785398" upper="0.785398" />
Expand Down Expand Up @@ -385,7 +385,7 @@
<link name="right_upperarm_virtual_2" />
<joint name="right_shoulder_Y" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="0 -1 0" />
<axis xyz="0 1 0" />
<parent link="right_upperarm_virtual_2" />
<child link="right_upperarm" />
<limit effort="52" velocity="6.0" lower="-1.5708" upper="3.14159" />
Expand Down Expand Up @@ -457,7 +457,7 @@
<link name="right_hand_virtual" />
<joint name="right_wrist_X" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="1 0 0" />
<axis xyz="-1 0 0" />
<parent link="right_hand_virtual" />
<child link="right_hand" />
<limit effort="100" velocity="6.0" lower="-0.785398" upper="0.785398" />
Expand Down Expand Up @@ -487,10 +487,10 @@
<link name="right_upperleg_virtual" />
<joint name="right_hip_X" type="revolute">
<origin xyz="0 0 0" rpy="0 -0 0" />
<axis xyz="1 0 0" />
<axis xyz="-1 0 0" />
<parent link="right_upperleg_virtual" />
<child link="right_upperleg_virtual_2" />
<limit effort="120" velocity="6.0" lower="-1.570795" upper="1.047196667" />
<limit effort="120" velocity="6.0" lower="-1.047196667" upper="1.570795" />
</joint>
<link name="right_upperleg_virtual_2"/>
<joint name="right_hip_Y" type="revolute">
Expand Down
Loading