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
a10c94eb
Commit
a10c94eb
authored
Nov 25, 2019
by
Guilhem Saurel
Browse files
Merge branch 'wxm-kinova-fixes' into 'devel'
Fix ANYmal-Kinova URDF See merge request
!24
parents
d4e656d4
8de7ed71
Pipeline
#6942
failed with stage
in 8 minutes and 20 seconds
Changes
2
Pipelines
1
Hide whitespace changes
Inline
Side-by-side
robots/anymal_b_simple_description/robots/anymal-kinova.urdf
View file @
a10c94eb
...
...
@@ -904,7 +904,7 @@
<inertia
ixx=
"0.00152031725204"
ixy=
"0"
ixz=
"0"
iyy=
"0.00152031725204"
iyz=
"0"
izz=
"0.00059816"
/>
</inertial>
</link>
<joint
name=
"j2s6s200_joint_1"
type=
"
continuous
"
>
<joint
name=
"j2s6s200_joint_1"
type=
"
revolute
"
>
<parent
link=
"j2s6s200_link_base"
/>
<child
link=
"j2s6s200_link_1"
/>
<axis
xyz=
"0 0 1"
/>
...
...
@@ -1033,7 +1033,7 @@
<inertia
ixx=
"0.0004321316048"
ixy=
"0"
ixz=
"0"
iyy=
"0.0004321316048"
iyz=
"0"
izz=
"9.26e-05"
/>
</inertial>
</link>
<joint
name=
"j2s6s200_joint_4"
type=
"
continuous
"
>
<joint
name=
"j2s6s200_joint_4"
type=
"
revolute
"
>
<parent
link=
"j2s6s200_link_3"
/>
<child
link=
"j2s6s200_link_4"
/>
<axis
xyz=
"0 0 1"
/>
...
...
@@ -1119,7 +1119,7 @@
<inertia
ixx=
"0.0003453236187"
ixy=
"0"
ixz=
"0"
iyy=
"0.0003453236187"
iyz=
"0"
izz=
"0.0005816"
/>
</inertial>
</link>
<joint
name=
"j2s6s200_joint_6"
type=
"
continuous
"
>
<joint
name=
"j2s6s200_joint_6"
type=
"
revolute
"
>
<parent
link=
"j2s6s200_link_5"
/>
<child
link=
"j2s6s200_link_6"
/>
<axis
xyz=
"0 0 1"
/>
...
...
robots/anymal_b_simple_description/srdf/anymal-kinova.srdf
View file @
a10c94eb
...
...
@@ -92,12 +92,12 @@
<joint
name=
"RH_HAA"
value=
"0.1"
/>
<joint
name=
"RH_HFE"
value=
"-0.7"
/>
<joint
name=
"RH_KFE"
value=
"1."
/>
<joint
name=
"j2s6s200_joint_1"
value=
"
1.5707"
/
>
<joint
name=
"j2s6s200_joint_2"
value=
"
2
.6
18"
/
>
<joint
name=
"j2s6s200_joint_3"
value=
"
-
1.
5707"
/
>
<joint
name=
"j2s6s200_joint_4"
value=
"
3.1415
"
/>
<joint
name=
"j2s6s200_joint_5"
value=
"2.
618"
/
>
<joint
name=
"j2s6s200_joint_6"
value=
"0."
/>
<joint
name=
"j2s6s200_joint_1"
value=
"
4.71238898038469"
/>
<!-- 3π / 2 --
>
<joint
name=
"j2s6s200_joint_2"
value=
"
3
.6
65191429188092"
/>
<!-- 7π / 6 --
>
<joint
name=
"j2s6s200_joint_3"
value=
"1.
0471975511965976"
/>
<!-- 1π / 3 --
>
<joint
name=
"j2s6s200_joint_4"
value=
"
0.0
"
/>
<joint
name=
"j2s6s200_joint_5"
value=
"2.
0943951023931953"
/>
<!-- 2π / 3 --
>
<joint
name=
"j2s6s200_joint_6"
value=
"0.
0
"
/>
</group_state>
<disable_collisions
link1=
"LF_HIP"
link2=
"LF_THIGH"
reason=
"Adjacent"
/>
...
...
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