Commit 9a117b65 authored by Guilhem Saurel's avatar Guilhem Saurel
Browse files

solo_description: update solo12.urdf

parent 06aa1e2e
......@@ -9,7 +9,7 @@
<!-- BASE LINK INERTIAL -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.63315091"/>
<mass value="1.16115091"/>
<!-- The base is extremely symmetrical. -->
<inertia ixx="0.00578574" ixy="0.0" ixz="0.0" iyy="0.01938108" iyz="0.0" izz="0.02476124"/>
</inertial>
......@@ -17,7 +17,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_body.obj"/>
<mesh filename="package://solo_description/meshes/stl/solo12/solo_12_base.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -27,7 +27,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_body.obj"/>
<mesh filename="package://solo_description/meshes/stl/solo12/solo_12_base.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -46,17 +46,38 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.19 0.1046 0"/>
<origin rpy="0 0 0" xyz="0.1946 0.0875 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FL_SHOULDER">
<!-- TODO: Update inertias. -->
<!-- create a dummy shoulder link to join the two joints -->
<!-- HAA VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_fl.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- HAA LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_fl.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0. 0. 0."/>
<!-- Adding extra weight for actuator module at shoulder. -->
<mass value="0.150"/>
<inertia ixx="0.00000001" ixy="0.0" ixz="0.0" iyy="0.00000001" iyz="0" izz="0.00000001"/>
<mass value="0.14853845"/>
<!-- HAA body inertia -->
<origin rpy="0 0 0" xyz="-0.07870700 0.01 0."/>
<inertia ixx="0.00003024" ixy="0.00004671" ixz="0.0" iyy="0.00041193" iyz="0.0" izz="0.00041107"/>
</inertial>
</link>
<joint name="FL_HFE" type="revolute">
......@@ -65,8 +86,7 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<!-- placement of the joint -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0.014 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -81,7 +101,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -91,7 +111,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -126,7 +146,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -136,7 +156,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -171,7 +191,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -181,7 +201,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -200,17 +220,38 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.19 -0.1046 0"/>
<origin rpy="0 0 0" xyz="0.1946 -0.0875 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FR_SHOULDER">
<!-- TODO: Update inertias. -->
<!-- create a dummy shoulder link to join the two joints -->
<!-- HAA VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_fr.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- HAA LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_fr.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0. 0. 0."/>
<!-- Adding extra weight for actuator module at shoulder. -->
<mass value="0.150"/>
<inertia ixx="0.00000001" ixy="0.0" ixz="0.0" iyy="0.00000001" iyz="0" izz="0.00000001"/>
<mass value="0.14853845"/>
<!-- HAA body inertia -->
<origin rpy="0 0 0" xyz="-0.07870700 -0.01 0."/>
<inertia ixx="0.00003024" ixy="-0.00004671" ixz="0.0" iyy="0.00041193" iyz="0.0" izz="0.00041107"/>
</inertial>
</link>
<joint name="FR_HFE" type="revolute">
......@@ -219,8 +260,7 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<!-- placement of the joint -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 -0.014 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -235,7 +275,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -245,7 +285,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -280,7 +320,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -290,7 +330,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -325,7 +365,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -335,7 +375,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -354,17 +394,38 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="-0.19 0.1046 0"/>
<origin rpy="0 0 0" xyz="-0.1946 0.0875 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="HL_SHOULDER">
<!-- TODO: Update inertias. -->
<!-- create a dummy shoulder link to join the two joints -->
<!-- HAA VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="-0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_hl.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- HAA LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="-0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_hl.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0. 0. 0."/>
<!-- Adding extra weight for actuator module at shoulder. -->
<mass value="0.150"/>
<inertia ixx="0.00000001" ixy="0.0" ixz="0.0" iyy="0.00000001" iyz="0" izz="0.00000001"/>
<mass value="0.14853845"/>
<!-- HAA body inertia -->
<origin rpy="0 0 0" xyz="0.07870700 0.01 0."/>
<inertia ixx="0.00003024" ixy="0.00004671" ixz="0.0" iyy="0.00041193" iyz="0.0" izz="0.00041107"/>
</inertial>
</link>
<joint name="HL_HFE" type="revolute">
......@@ -373,8 +434,7 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<!-- placement of the joint -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0.014 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -389,7 +449,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -399,7 +459,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -434,7 +494,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -444,7 +504,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_left_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -479,7 +539,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -489,7 +549,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -508,17 +568,38 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="-0.19 -0.1046 0"/>
<origin rpy="0 0 0" xyz="-0.1946 -0.0875 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="HR_SHOULDER">
<!-- TODO: Update inertias. -->
<!-- create a dummy shoulder link to join the two joints -->
<!-- HAA VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="-0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_hr.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- HAA LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="-0.01950 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/stl/solo12/solo12_hip_fe_hr.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0. 0. 0."/>
<!-- Adding extra weight for actuator module at shoulder. -->
<mass value="0.150"/>
<inertia ixx="0.00000001" ixy="0.0" ixz="0.0" iyy="0.00000001" iyz="0" izz="0.00000001"/>
<mass value="0.14853845"/>
<!-- HAA body inertia -->
<origin rpy="0 0 0" xyz="0.07870700 -0.01 0."/>
<inertia ixx="0.00003024" ixy="-0.00004671" ixz="0.0" iyy="0.00041193" iyz="0.0" izz="0.00041107"/>
</inertial>
</link>
<joint name="HR_HFE" type="revolute">
......@@ -527,8 +608,7 @@
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<!-- placement of the joint -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 -0.014 0"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -543,7 +623,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -553,7 +633,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_upper_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_upper_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -588,7 +668,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -598,7 +678,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_lower_leg_right_side.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_lower_leg_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -633,7 +713,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -643,7 +723,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://solo_description/meshes/obj/with_foot/solo_foot.obj"/>
<mesh filename="package://solo_description/meshes/stl/with_foot/solo_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
......@@ -657,4 +737,3 @@
</link>
<!-- END LOWER LEG LINK -->
</robot>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment