Skip to content
New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Update inertias #35

Merged
merged 2 commits into from
May 11, 2022
Merged
Changes from 1 commit
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
65 changes: 38 additions & 27 deletions buoy_description/models/mbari_wec/model.sdf.em
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,10 @@ tether_top_length = 2.0

num_tether_bottom_links = 10

# Heave cone
heave_total_mass = 817
trefoil_mass = 10

###################
# Computed values #
###################
Expand All @@ -48,14 +52,15 @@ tether_bottom_link_cylinder.mass_matrix(tether_bottom_link_mm)
<link name="Buoy">
<pose relative_to="__model__">0 0 0 0 0 0</pose>
<inertial>
<mass>1080</mass>
<pose>0 0 2.13 0 0 0</pose>
<mass>1400</mass>
<inertia>
<ixx>10000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>10000</iyy>
<iyz>0</iyz>
<izz>1000</izz>
<ixx>1429</ixx>
<ixy>6.77</ixy>
<ixz>4.69</ixz>
<iyy>670.31</iyy>
<iyz>30.5</iyz>
<izz>1476</izz>
</inertia>
</inertial>
<visual name="visual">
Expand All @@ -76,14 +81,15 @@ tether_bottom_link_cylinder.mass_matrix(tether_bottom_link_mm)
<link name="PTO">
<pose relative_to="Buoy">0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 -3.67 0 0 0</pose>
<mass>605</mass>
<inertia>
<ixx>10000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>10000</iyy>
<iyz>0</iyz>
<izz>1000</izz>
<ixx>3219</ixx>
<ixy>-0.43</ixy>
<ixz>-2.56</ixz>
<iyy>3219</iyy>
<iyz>3.37</iyz>
<izz>7.28</izz>
</inertia>
</inertial>
<visual name="visual">
Expand Down Expand Up @@ -112,13 +118,15 @@ tether_bottom_link_cylinder.mass_matrix(tether_bottom_link_mm)
<pose relative_to="PTO">0 0 @(piston_z_offset) 0 0 0</pose>
<inertial>
<mass>48</mass>
<pose>0 0 -2.57934 0 0 0</pose>
<inertia>
<ixx>10000</ixx>
<!-- TODO(chapulina) Get real values -->
<ixx>128</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>10000</iyy>
<iyy>128</iyy>
<iyz>0</iyz>
<izz>1000</izz>
<izz>0.0216</izz>
</inertia>
</inertial>
<visual name="visual">
Expand Down Expand Up @@ -241,14 +249,15 @@ tether_bottom_link_cylinder.mass_matrix(tether_bottom_link_mm)
<link name="HeaveCone">
<pose relative_to="PistonBottom">0 0 -@(tether_length) 0 0 0</pose>
<inertial>
<mass>1000</mass>
<pose>0 0 -1.25 0 0 0</pose>
<mass>@(heave_total_mass - trefoil_mass)</mass>
<inertia>
<ixx>10000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>10000</iyy>
<iyz>0</iyz>
<izz>1000</izz>
<ixx>339.8</ixx>
<ixy>0.16</ixy>
<ixz>-0.29</ixz>
<iyy>343.73</iyy>
<iyz>0.33</iyz>
<izz>613.52</izz>
</inertia>
</inertial>
<visual name="visual">
Expand All @@ -269,14 +278,16 @@ tether_bottom_link_cylinder.mass_matrix(tether_bottom_link_mm)
<link name="Trefoil">
<pose relative_to="HeaveCone">0 0 0 0 0 0</pose>
<inertial>
<mass>10</mass>
<pose>0 0 -1.25 0 0 0</pose>
<!-- TODO(chapulina) Get real values -->
<mass>@(trefoil_mass)</mass>
<inertia>
<ixx>10000</ixx>
<ixx>10</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>10000</iyy>
<iyy>10</iyy>
<iyz>0</iyz>
<izz>1000</izz>
<izz>19.9</izz>
</inertia>
</inertial>
<visual name="visual">
Expand Down