Skip to content

Commit

Permalink
Add tethys model with DVL sensor (#9)
Browse files Browse the repository at this point in the history
* add tethys model containing various sensors
* Added mass demo with two spheres (#24)


Signed-off-by: Ian Chen <[email protected]>
Signed-off-by: Dharini Dutia <[email protected]>
Co-authored-by: Dharini Dutia <[email protected]>
  • Loading branch information
iche033 and quarkytale authored Sep 29, 2023
1 parent e41f701 commit 8954ffb
Show file tree
Hide file tree
Showing 6 changed files with 612 additions and 0 deletions.
8 changes: 8 additions & 0 deletions harmonic_demo/Spheres/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<?xml version="1.0"?>
<model>
<name>Spheres</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>


</model>
79 changes: 79 additions & 0 deletions harmonic_demo/Spheres/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
<?xml version='1.0' ?>
<sdf version="1.6">
<model name="spheres">
<link name="sphere_no_added_mass">
<inertial>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="sphere_no_added_mass_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>

<visual name="sphere_no_added_mass_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
</link>

<link name="sphere_with_added_mass">
<pose relative_to="sphere_no_added_mass">0 -1 0 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
<mass>1.0</mass>
<fluid_added_mass>
<xx>261.666</xx>
<yy>261.666</yy>
<zz>261.666</zz>
</fluid_added_mass>
</inertial>
<collision name="sphere_with_added_mass_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>

<visual name="sphere_with_added_mass_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>

</model>
</sdf>
15 changes: 15 additions & 0 deletions harmonic_demo/Tethys Sensors/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>Tethys Sensors</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>

<author>
<name>Ian Chen</name>
<email>[email protected]</email>
</author>

<description>
3D model of MBARI LRAUV Tethys, with DV, IMU, and magnetometer sensors and plugins. Adapted from https://github.com/osrf/lrauv
</description>
</model>
205 changes: 205 additions & 0 deletions harmonic_demo/Tethys Sensors/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,205 @@
<?xml version="1.0"?>

<sdf version="1.9">
<model name="tethys">

<include merge="true">
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>

<!-- Sensors -->
<experimental:params>
<!--
Teledyne Pathfinder DVL
See https://www.manualslib.com/manual/1447288/Teledyne-Pathfinder.html
for further reference.
-->
<sensor
element_id="base_link" action="add"
name="teledyne_pathfinder_dvl"
type="custom" gz:type="dvl">
<!-- Account for DVL mounting position and base link rotation -->
<pose degrees="true">-0.60 0 -0.16 0 0 180</pose>
<always_on>1</always_on>
<update_rate>1</update_rate>
<topic>/tethys/dvl/velocity</topic>
<gz:dvl>
<type>phased_array</type>
<arrangement degrees="true">
<beam id="1">
<aperture>2.1</aperture>
<rotation>45</rotation>
<tilt>30</tilt>
</beam>
<beam>
<aperture>2.1</aperture>
<rotation>135</rotation>
<tilt>30</tilt>
</beam>
<beam>
<aperture>2.1</aperture>
<rotation>-45</rotation>
<tilt>30</tilt>
</beam>
<beam>
<aperture>2.1</aperture>
<rotation>-135</rotation>
<tilt>30</tilt>
</beam>
</arrangement>
<tracking>
<bottom_mode>
<when>best</when>
<noise type="gaussian">
<!-- +/- 0.4 cm/s precision at 10 m/s within 2 stddevs -->
<stddev>0.002</stddev>
</noise>
<visualize>false</visualize>
</bottom_mode>
<!-- Uncomment to enable water_mass_mode.
Requires Environment-Preload plugin -->
<!--
<water_mass_mode>
<when>best</when>
<water_velocity>
<x>eastward_sea_water_velocity_meter_per_sec</x>
<y>northward_sea_water_velocity_meter_per_sec</y>
</water_velocity>
<boundaries>
<near>20.</near>
<far>60.</far>
</boundaries>
<bins>10</bins>
<noise type="gaussian">
<stddev>0.0035</stddev>
</noise>
<visualize>false</visualize>
</water_mass_mode>
-->
</tracking>
<!-- Roughly 1 m resolution at a 100m -->
<resolution>0.01</resolution>
<!-- Approximate maximum range @ ~14.4v -->
<maximum_range>80.</maximum_range>
<minimum_range>0.1</minimum_range>
<!-- ENU to SFM -->
<reference_frame>0 0 0 0 0 -1.570796</reference_frame>
</gz:dvl>
</sensor>
<!--
Sparton AHRS-M2 arrangement of IMU + Magnetometer
See https://www.spartonnavex.com/product/ahrs-m2 for
AHRS specifications and additional documentation.
-->
<sensor
element_id="base_link"
action="add"
name="sparton_ahrs_m2_imu"
type="imu">
<!--IMU in a Sparton AHRS-M2 -->
<always_on>1</always_on>
<!-- Flip body frame to match FSK frame convention -->
<!--
Also account for model being rotated 180 degrees
See https://github.com/osrf/lrauv/issues/80.
-->
<pose degrees="true">0 0 0 180 0 180</pose>
<imu>
<orientation_reference_frame>
<localization>NED</localization>
</orientation_reference_frame>
<enable_orientation>1</enable_orientation>
<linear_acceleration>
<!--
Use zero-mean gaussian distributions for each
linear acceleration component and its (turn on)
bias.
Standard deviation is assumed to be the same for all
linear acceleration components. It is computed from
reported noise density ND = 250 ug/√Hz and chosen
sample rate SR = 10 Hz as ND √SR.
Standard deviation is assumed to be the same for all
linear acceleration component (turn on) biases. It is
made equal to the reported bias stability BS = 0.07441 mg.
-->
<x>
<noise type="gaussian">
<stddev>0.00775283755402256</stddev>
<bias_stddev>0.007297128265</bias_stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<stddev>0.00775283755402256</stddev>
<bias_stddev>0.007297128265</bias_stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<stddev>0.00775283755402256</stddev>
<bias_stddev>0.007297128265</bias_stddev>
</noise>
</z>
</linear_acceleration>
<angular_velocity>
<!--
Use zero-mean gaussian distributions for each
angular velocity component and its (turn on)
bias.
Standard deviation is assumed to be the same for all
angular velocity components. It is computed from
reported noise density ND = 0.04 °/s/√Hz and chosen
sample rate SR = 10 Hz as ND √SR.
Standard deviation is assumed to be the same for all
angular velocity component (turn on) biases. It is made
equal to the reported bias stability BS = 6.415 °/hr.
-->
<x>
<noise type="gaussian">
<stddev>0.0022076862812880228</stddev>
<bias_stddev>0.0017819444444444445</bias_stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<stddev>0.0022076862812880228</stddev>
<bias_stddev>0.0017819444444444445</bias_stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<stddev>0.0022076862812880228</stddev>
<bias_stddev>0.0017819444444444445</bias_stddev>
</noise>
</z>
</angular_velocity>
</imu>
<update_rate>10</update_rate>
<topic>/tethys/ahrs/imu</topic>
</sensor>
<!--Magnetometer in a Sparton AHRS-M2 -->
<sensor
element_id="base_link"
action="add"
name="sparton_ahrs_m2_magnetometer"
type="magnetometer">
<always_on>1</always_on>
<update_rate>10</update_rate>
<!-- Flip body frame to match FSK frame convention -->
<!--
Also account for model being rotated 180 degrees
See https://github.com/osrf/lrauv/issues/80.
-->
<pose degrees="true">0 0 0 180 0 180</pose>
<topic>/tethys/ahrs/magnetometer</topic>
</sensor>
</experimental:params>

</include>
</model>
</sdf>
Loading

0 comments on commit 8954ffb

Please sign in to comment.