Skip to content
GitLab
Menu
Projects
Groups
Snippets
Loading...
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
U2IS
aquanaute
Commits
3ba6216e
Commit
3ba6216e
authored
Jul 03, 2020
by
Ricardo Rico Uribe
Browse files
corrected for inertias
parent
49a7ebda
Changes
1
Hide whitespace changes
Inline
Side-by-side
aquanaute_description/urdf/aquanaute.urdf
View file @
3ba6216e
...
@@ -31,13 +31,21 @@
...
@@ -31,13 +31,21 @@
<!-- * * * Link Definitions * * * -->
<!-- * * * Link Definitions * * * -->
<link
name=
"base_link"
>
<link
name=
"base_link"
>
<!--
<visual>
<origin
rpy=
"0.0 0 0"
xyz=
"0 0 0"
/>
<geometry>
<sphere
radius=
"0.001"
/>
</geometry>
<material
name=
"blue"
/>
</visual>
</link>
<link
name=
"platform_link"
>
<inertial>
<inertial>
<origin xyz="
0 0 0
" rpy="0 0 0"/>
<origin
xyz=
"
-0.024 0 -0007
"
rpy=
"0 0 0"
/>
<mass value="1
0.5
"/>
<mass
value=
"1
6
"
/>
<inertia ixx="
0.0002835
" ixy="0.0" ixz="0.0" iyy="
0.0002835
" iyz="0.0" izz="
0.000324
"/>
<inertia
ixx=
"
4.206
"
ixy=
"0.0"
ixz=
"
-
0.0
31
"
iyy=
"
4.588
"
iyz=
"0.0"
izz=
"
8.785
"
/>
</inertial>
</inertial>
-->
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
...
@@ -56,13 +64,12 @@
...
@@ -56,13 +64,12 @@
</link>
</link>
<link
name=
"right_hull_link"
>
<link
name=
"right_hull_link"
>
<!--
<inertial>
<inertial>
<origin xyz="
0 0 0
" rpy="0 0 0"/>
<origin
xyz=
"
-0.124 0 -0.168
"
rpy=
"0 0 0"
/>
<mass value="10.5"/>
<mass
value=
"10.
4
5"
/>
<inertia ixx="0.
0002835
" ixy="
0.0
" ixz="0.0" iyy="
0.0002835
" iyz="
0.0
" izz="
0.000324
"/>
<inertia
ixx=
"0.
244
"
ixy=
"
3.346
"
ixz=
"0.0
09
"
iyy=
"
4.974
"
iyz=
"
-8.274
"
izz=
"
4.965
"
/>
</inertial>
</inertial>
-->
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<geometry>
...
@@ -80,13 +87,11 @@
...
@@ -80,13 +87,11 @@
</link>
</link>
<link
name=
"left_hull_link"
>
<link
name=
"left_hull_link"
>
<!--
<inertial>
<inertial>
<origin xyz="
0 0 0
" rpy="0 0 0"/>
<origin
xyz=
"
-0.124 0 -0.168
"
rpy=
"0 0 0"
/>
<mass value="10.5"/>
<mass
value=
"10.
4
5"
/>
<inertia ixx="0.
0002835
" ixy="
0.0
" ixz="0.0" iyy="
0.0002835
" iyz="
0.0
" izz="
0.000324
"/>
<inertia
ixx=
"0.
244
"
ixy=
"
3.346
"
ixz=
"0.0
09
"
iyy=
"
4.974
"
iyz=
"
-8.274
"
izz=
"
4.965
"
/>
</inertial>
</inertial>
-->
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
...
@@ -105,13 +110,11 @@
...
@@ -105,13 +110,11 @@
</link>
</link>
<link
name=
"motor_link"
>
<link
name=
"motor_link"
>
<!--
<inertial>
<inertial>
<origin xyz="
0 0 0
" rpy="0 0 0"/>
<origin
xyz=
"
-0.133 0 -0.391
"
rpy=
"0 0 0"
/>
<mass value="
10.5
"/>
<mass
value=
"
6.6
"
/>
<inertia ixx="0.0
002835
" ixy="
0.0
" ixz="0.0" iyy="0.
0002835
" iyz="
0.0
" izz="0.0
0032
4"/>
<inertia
ixx=
"0.0
72
"
ixy=
"
3.604
"
ixz=
"
-
0.0
11
"
iyy=
"0.
111
"
iyz=
"
5.484
"
izz=
"0.04
2
"
/>
</inertial>
</inertial>
-->
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
...
@@ -130,13 +133,12 @@
...
@@ -130,13 +133,12 @@
</link>
</link>
<link
name=
"sensor_frame_link"
>
<link
name=
"sensor_frame_link"
>
<!--
<inertial>
<inertial>
<origin xyz="
0 0 0
" rpy="0 0 0"/>
<origin
xyz=
"
-0.007 0 0.379
"
rpy=
"0 0 0"
/>
<mass value="1
0.5
"/>
<mass
value=
"1
.8
"
/>
<inertia ixx="0.
0002835
" ixy="0.0" ixz="0.0" iyy="0.
0002835"
iyz="0.0" izz="0.0
00324
"/>
<inertia
ixx=
"0.
308
"
ixy=
"0.0
0
"
ixz=
"0.0
07
"
iyy=
"0.
297"
iyz=
"0.0
0
"
izz=
"0.0
22
"
/>
</inertial>
</inertial>
-->
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<geometry>
...
@@ -154,14 +156,20 @@
...
@@ -154,14 +156,20 @@
</link>
</link>
<!-- * * * Joint Definitions * * * -->
<!-- * * * Joint Definitions * * * -->
<joint
name=
"
right_hull_
platform_joint"
type=
"fixed"
>
<joint
name=
"platform_
base_
joint"
type=
"fixed"
>
<parent
link=
"base_link"
/>
<parent
link=
"base_link"
/>
<child
link=
"platform_link"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
</joint>
<joint
name=
"right_hull_platform_joint"
type=
"fixed"
>
<parent
link=
"platform_link"
/>
<child
link=
"right_hull_link"
/>
<child
link=
"right_hull_link"
/>
<origin
xyz=
"-0.05 -0.7 -0.036"
rpy=
"0 0 0"
/>
<origin
xyz=
"-0.05 -0.7 -0.036"
rpy=
"0 0 0"
/>
</joint>
</joint>
<joint
name=
"left_hull_platform_joint"
type=
"fixed"
>
<joint
name=
"left_hull_platform_joint"
type=
"fixed"
>
<parent
link=
"
base
_link"
/>
<parent
link=
"
platform
_link"
/>
<child
link=
"left_hull_link"
/>
<child
link=
"left_hull_link"
/>
<origin
xyz=
"-0.05 0.7 -0.036"
rpy=
"0 0 0"
/>
<origin
xyz=
"-0.05 0.7 -0.036"
rpy=
"0 0 0"
/>
</joint>
</joint>
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a 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