Skip to content

Commit

Permalink
Create new model to hold sensors and plugins
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Nov 2, 2021
1 parent 0f0d722 commit b8da409
Show file tree
Hide file tree
Showing 5 changed files with 267 additions and 488 deletions.
2 changes: 1 addition & 1 deletion lrauv_description/models/tethys/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@
<size>0.1 0.1 0.02</size>
</box>
</geometry>
</collision>
</collision>

<visual name= "visual">
<pose>-1.05 0 0 0 0 0</pose>
Expand Down
15 changes: 15 additions & 0 deletions lrauv_description/models/tethys_equiped/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>Tethys equiped</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>

<author>
<name>Mabel Zhang</name>
<email>[email protected]</email>
</author>

<description>
3D model of MBARI LRAUV Tethys, with sensors and plugins.
</description>
</model>
190 changes: 190 additions & 0 deletions lrauv_description/models/tethys_equiped/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,190 @@
<?xml version="1.0"?>
<sdf version="1.9">
<model name="tethys">
<include merge="true">
<uri>tethys</uri>

<!-- Sensors -->
<experimental:params>
<sensor
element_id="base_link"
action="add"
name="salinity_sensor"
type="custom"
ignition:type="salinity">
<always_on>1</always_on>
<update_rate>2</update_rate>
<topic>/model/tethys/salinity</topic>
<ignition:salinity>
<noise type="gaussian">
<mean>0.00001</mean>
<stddev>0.00001</stddev>
</noise>
</ignition:salinity>
</sensor>
<sensor
element_id="base_link"
action="add"
name="temperature_sensor"
type="custom"
ignition:type="temperature">
<always_on>1</always_on>
<update_rate>2</update_rate>
<topic>/model/tethys/temperature</topic>
<ignition:temperature>
<noise type="gaussian">
<mean>0.00001</mean>
<stddev>0.00001</stddev>
</noise>
</ignition:temperature>
</sensor>
<sensor
element_id="base_link"
action="add"
name="chlorophyll_sensor"
type="custom"
ignition:type="chlorophyll">
<always_on>1</always_on>
<update_rate>2</update_rate>
<topic>/model/tethys/chlorophyll</topic>
<ignition:chlorophyll>
<noise type="gaussian">
<mean>0.00001</mean>
<stddev>0.00001</stddev>
</noise>
</ignition:chlorophyll>
</sensor>
<sensor
element_id="base_link"
action="add"
name="current_sensor"
type="custom"
ignition:type="current">
<always_on>1</always_on>
<update_rate>2</update_rate>
<topic>/model/tethys/current</topic>
<ignition:current>
<noise type="gaussian">
<mean>0.00001</mean>
<stddev>0.00001</stddev>
</noise>
</ignition:current>
</sensor>
</experimental:params>
<!-- Joint controllers -->
<plugin
filename="ignition-gazebo-joint-position-controller-system"
name="ignition::gazebo::systems::JointPositionController">
<joint_name>horizontal_fins_joint</joint_name>
<p_gain>0.1</p_gain>
</plugin>
<plugin
filename="ignition-gazebo-joint-position-controller-system"
name="ignition::gazebo::systems::JointPositionController">
<joint_name>vertical_fins_joint</joint_name>
<p_gain>0.1</p_gain>
</plugin>
<plugin
filename="ThrusterPlugin"
name="tethys::Thruster">
<namespace>tethys</namespace>
<joint_name>propeller_joint</joint_name>
<thrust_coefficient>0.004422</thrust_coefficient>
<fluid_density>1000</fluid_density>
<propeller_diameter>0.2</propeller_diameter>
<velocity_control>true</velocity_control>
</plugin>
<plugin
filename="JointPositionPlugin"
name="tethys::TethysJointPlugin">
<joint_name>battery_joint</joint_name>
</plugin>
<!-- Lift and drag -->
<!-- Vertical fin -->
<plugin
filename="ignition-gazebo-lift-drag-system"
name="ignition::gazebo::systems::LiftDrag">
<air_density>1000</air_density>
<cla>4.13</cla>
<cla_stall>-1.1</cla_stall>
<cda>0.2</cda>
<cda_stall>0.03</cda_stall>
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<upward>0 1 0</upward>
<forward>1 0 0</forward>
<link_name>vertical_fins</link_name>
<cp>0 0 0</cp>
</plugin>
<!-- Horizontal fin -->
<plugin
filename="ignition-gazebo-lift-drag-system"
name="ignition::gazebo::systems::LiftDrag">
<air_density>1000</air_density>
<cla>4.13</cla>
<cla_stall>-1.1</cla_stall>
<cda>0.2</cda>
<cda_stall>0.03</cda_stall>
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<upward>0 0 1</upward>
<forward>1 0 0</forward>
<link_name>horizontal_fins</link_name>
<cp>0 0 0</cp>
</plugin>
<!-- Interface with LRAUV Main Vehicle Application for each vehicle -->
<plugin
filename="TethysCommPlugin"
name="tethys::TethysCommPlugin">
<namespace>tethys</namespace>
<command_topic>tethys/command_topic</command_topic>
<state_topic>tethys/state_topic</state_topic>
</plugin>
<plugin
filename="HydrodynamicsPlugin"
name="tethys::HydrodynamicsPlugin">
<link_name>base_link</link_name>
<enable_coriolis>false</enable_coriolis>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUU>-6.2282</xUU>
<xU>0</xU>
<yVV>-601.27</yVV>
<yV>0</yV>
<zWW>-601.27</zWW>
<zW>0</zW>
<kPP>-0.1916</kPP>
<kP>0</kP>
<mQQ>-632.698957</mQQ>
<mQ>0</mQ>
<nRR>-632.698957</nRR>
<nR>0</nR>
</plugin>
<plugin
filename="BuoyancyEnginePlugin"
name="tethys::BuoyancyEnginePlugin">
<link_name>buoyancy_engine</link_name>
<namespace>tethys</namespace>
<min_volume>0.000080</min_volume>
<neutral_volume>0.0005</neutral_volume>
<default_volume>0.0005</default_volume>
<max_volume>0.000955</max_volume>
<max_inflation_rate>0.000003</max_inflation_rate>
</plugin>
<plugin
filename="ignition-gazebo-detachable-joint-system"
name="ignition::gazebo::systems::DetachableJoint">
<parent_link>base_link</parent_link>
<child_model>drop_weight</child_model>
<child_link>drop_weight</child_link>
<topic>/model/tethys/drop_weight</topic>
</plugin>
</include>
</model>
</sdf>
Loading

0 comments on commit b8da409

Please sign in to comment.