Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Gepetto
example-robot-data
Commits
014f4c41
Commit
014f4c41
authored
Nov 26, 2019
by
Wolfgang Merkt
Browse files
hyq_description: Add inertia information for simulator
parent
0bd033fc
Changes
1
Hide whitespace changes
Inline
Side-by-side
robots/hyq_description/robots/hyq_no_sensors.urdf
View file @
014f4c41
...
...
@@ -73,6 +73,10 @@ is the world frame). For more, see http://ros.org/wiki/xacro -->
<!-- Links -->
<!-- Footprint link -->
<link
name=
"base_link"
>
<inertial>
<mass
value=
"1e-6"
/>
<inertia
ixx=
"1e-6"
ixy=
"1e-6"
ixz=
"1e-6"
iyy=
"1e-6"
iyz=
"1e-6"
izz=
"1e-6"
/>
</inertial>
<visual>
<geometry>
<cylinder
length=
"0.01"
radius=
"0.01"
/>
...
...
@@ -203,6 +207,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro -->
</link>
<!-- Foot link -->
<link
name=
"lf_foot"
>
<contact>
<lateral_friction
value=
"1"
/>
<stiffness
value=
"30000"
/>
<damping
value=
"1000"
/>
</contact>
<inertial>
<mass
value=
"1e-6"
/>
<inertia
ixx=
"1e-6"
ixy=
"1e-6"
ixz=
"1e-6"
iyy=
"1e-6"
iyz=
"1e-6"
izz=
"1e-6"
/>
</inertial>
<collision>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<geometry>
...
...
@@ -409,6 +422,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro -->
</link>
<!-- Foot link -->
<link
name=
"rf_foot"
>
<contact>
<lateral_friction
value=
"1"
/>
<stiffness
value=
"30000"
/>
<damping
value=
"1000"
/>
</contact>
<inertial>
<mass
value=
"1e-6"
/>
<inertia
ixx=
"1e-6"
ixy=
"1e-6"
ixz=
"1e-6"
iyy=
"1e-6"
iyz=
"1e-6"
izz=
"1e-6"
/>
</inertial>
<collision>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<geometry>
...
...
@@ -615,6 +637,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro -->
</link>
<!-- Foot link -->
<link
name=
"lh_foot"
>
<contact>
<lateral_friction
value=
"1"
/>
<stiffness
value=
"30000"
/>
<damping
value=
"1000"
/>
</contact>
<inertial>
<mass
value=
"1e-6"
/>
<inertia
ixx=
"1e-6"
ixy=
"1e-6"
ixz=
"1e-6"
iyy=
"1e-6"
iyz=
"1e-6"
izz=
"1e-6"
/>
</inertial>
<collision>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<geometry>
...
...
@@ -821,6 +852,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro -->
</link>
<!-- Foot link -->
<link
name=
"rh_foot"
>
<contact>
<lateral_friction
value=
"1"
/>
<stiffness
value=
"30000"
/>
<damping
value=
"1000"
/>
</contact>
<inertial>
<mass
value=
"1e-6"
/>
<inertia
ixx=
"1e-6"
ixy=
"1e-6"
ixz=
"1e-6"
iyy=
"1e-6"
iyz=
"1e-6"
izz=
"1e-6"
/>
</inertial>
<collision>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<geometry>
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment