Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
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
21 changes: 21 additions & 0 deletions models/dave_object_models/models/torpedo_mk48/inertial_calcs.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
'''
iPython script to calculate inertial properties
'''
from math import pi

# Mass [kg]
m = 1558
# Length and dia [m]
l = 5.8
d = 0.53
# Volume
v = pi*(d/2)**2*l

# "mass" in water [kg]
m_water = m - v*1000
print("Mass in water %f kg"%m_water)

ixx = 0.5 * m_water * (d/2)**2
iyy = (0.25 * m_water * (d/2)**2) + (1.0/12.0 * m_water * l**2)

print("ixx = %f, iyy = izz = %.f"%(ixx,iyy))
115 changes: 115 additions & 0 deletions models/dave_object_models/models/torpedo_mk48/meshes/torpedo_mk48.dae

Large diffs are not rendered by default.

Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.

Large diffs are not rendered by default.

16 changes: 16 additions & 0 deletions models/dave_object_models/models/torpedo_mk48/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>

<model>
<name>torpedo_mk48</name>
<version>1.0</version>
<sdf version='1.6'>model.sdf</sdf>

<author>
<name>Brian Bingham</name>
<email>[email protected]</email>
</author>

<description>
Torpedo
</description>
</model>
35 changes: 35 additions & 0 deletions models/dave_object_models/models/torpedo_mk48/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
<?xml version="1.0"?>
<sdf version="1.6">
<model name="torpedo_mk48">
<static>false</static>
<link name="base_link">
<inertial>
<!-- See python script in model folder for calcs -->
<mass>278</mass>
<inertia>
<ixx>9.8</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>785</iyy>
<iyz>0.0</iyz>
<izz>785</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>file://torpedo_mk48/meshes/torpedo_mk48.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>file://torpedo_mk48/meshes/torpedo_mk48_collision.dae</uri>
</mesh>
</geometry>
</collision>
</link>
</model>
</sdf>
14 changes: 14 additions & 0 deletions models/dave_worlds/worlds/dave_ocean_models.world
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,12 @@
<uri>model://torpedo_mk46</uri>
</include>

<include>
<name>torpedo_mk48</name>
<pose>13 -1.5 -94 0 0 0</pose>
<uri>model://torpedo_mk48</uri>
</include>

<include>
<name>sonobuoy</name>
<pose>13 -2 -94 0 0 0</pose>
Expand Down Expand Up @@ -223,6 +229,14 @@
<uri>https://fuel.ignitionrobotics.org/1.0/Cole/models/Lionfish</uri>
</include>

<!-- Still pending
<include>
<name>airplane_wreck</name>
<pose>20 -11 -94 0 0 0</pose>
<uri>model://airplane_wreck</uri>
</include>
-->

<include>
<pose>35 -10 -94 0 0 0</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/Cole/models/Sunken Ship</uri>
Expand Down