Skip to content
This repository was archived by the owner on Mar 18, 2025. It is now read-only.

Strip and add back components #82

Closed
wants to merge 5 commits into from
Closed
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
52 changes: 25 additions & 27 deletions lrauv_description/models/tethys/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,34 +9,35 @@
<link name="base_link">
<inertial>
<!-- to offset battery CoM before getting real parameters for vehicle without battery -->
<!--pose>0 0.0236 0 0 0 0</pose-->
<pose>-0.119779049 0 0 0 0 0</pose>
<!-- 146.5671 subtracted by battery mass -->
<mass>114.8364</mass>
<!--<mass>146.5671</mass>-->
<!-- TODO: Get inertial matrix of base link WITHOUT battery -->
<inertia>
<!--ixx>3.000000</ixx>
<ixx>3.000000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>41.980233</iyy>
<iyz>0</iyz>
<izz>41.980233</izz-->

<izz>41.980233</izz>
<!-- Guesstimated (decreased by 1/5) to account for battery -->
<ixx>2.4</ixx>
<!--<ixx>2.4</ixx>
<ixy>0</ixy>
<ixz>0.0004</ixz>
<iyy>33.5841864</iyy>
<iyz>0</iyz>
<izz>33.5841864</izz>
<izz>33.5841864</izz>-->

</inertia>
</inertial>

<collision name="main_body_buoyancy">
<pose>0 0 0.007 0 0 0</pose>
<pose>-0.1181 0 0.007 0 0 0</pose>
<geometry>
<box>
<size>2 0.3 0.245945166667</size>
<!--<size>2 0.2 0.36891775</size>-->
</box>
</geometry>
</collision>
Expand Down Expand Up @@ -72,7 +73,7 @@
</link>

<!-- Horizontal fins -->
<link name="horizontal_fins">
<!--<link name="horizontal_fins">
<pose>1.05 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 1.57 0 0.5</pose>
Expand Down Expand Up @@ -124,10 +125,10 @@
</script>
</material>
</visual>
</link>
</link>-->

<!-- Vertical fins -->
<link name="vertical_fins">
<!--<link name="vertical_fins">
<pose>1.05 0 0 0 0 0</pose>
<inertial>
<mass>0.2</mass>
Expand Down Expand Up @@ -178,10 +179,10 @@
</script>
</material>
</visual>
</link>
</link>-->

<!-- Propeller -->
<link name="propeller">
<!--<link name="propeller">
<pose>1.43162 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 1.570796 0 0</pose>
Expand Down Expand Up @@ -233,17 +234,18 @@
</script>
</material>
</visual>
</link>
</link>-->

<!-- Battery -->
<!-- No separate collision for battery, because it is inside the vehicle.
Additional collision requires buoyancy volume recalculation. -->
<link name="battery">
<!-- TODO: On hold till mesh center adjusted to aft dome, then it will be 0.563, 0, 0.024. -->
<pose>0 0 0 0 0 0</pose>
<link name="battery">
<!--TODO: On hold till mesh center adjusted to aft dome, then it will be 0.563, 0, 0.024.-->

<inertial>
<!-- Non-zero y creates roll. Not fun to tune without actual base link inertia minus battery-->
<!--pose>0 -0.0236 0 0 0 0</pose-->
<pose>-0.119779049 0 0 0 0 0</pose>
<mass>31.7307</mass>
<inertia>
<ixx>0.2327</ixx>
Expand All @@ -269,9 +271,9 @@
</visual>
</link>

<link name="buoyancy_engine">
<!--<link name="buoyancy_engine">-->
<!-- TODO: Determine location of buoyancy engine -->
<pose>0.4 0 0 0 0 0</pose>
<!--<pose>0.4 0 0 0 0 0</pose>-->

<!-- TODO: Remove inertial and collision

Expand All @@ -285,7 +287,7 @@
(why?), so removing them makes the vehicle unstable.

-->
<inertial>
<!--<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.3</mass>
<inertia>
Expand All @@ -304,10 +306,10 @@
</box>
</geometry>
</collision>
</link>
</link>-->

<!-- Joints -->
<joint name="buoyancy_engine_joint" type="fixed">
<!--<joint name="buoyancy_engine_joint" type="fixed">
<pose>0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>buoyancy_engine</child>
Expand Down Expand Up @@ -356,7 +358,7 @@
<velocity>-1</velocity>
</limit>
</axis>
</joint>
</joint>-->

<!-- positive joint values move mass forward -->
<joint name="battery_joint" type="prismatic">
Expand All @@ -376,16 +378,12 @@

<!-- Drop weight -->
<link name="drop_weight">
<pose>0 0 0 0 0 0</pose>
<pose>0.128 0 -0.142 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>0.000143971303</ixx>
<ixy>0.000000000008</ixy>
<ixz>-0.000000000224</ixz>
<iyy>0.000140915448</iyy>
<iyz>-0.000025236433</iyz>
<izz>0.000033571862</izz>
</inertia>
</inertial>
Expand Down
56 changes: 28 additions & 28 deletions lrauv_description/models/tethys_equipped/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<uri>tethys</uri>

<!-- Sensors -->
<experimental:params>
<!--<experimental:params>
<sensor
element_id="base_link"
action="add"
Expand Down Expand Up @@ -74,9 +74,9 @@
</noise>
</ignition:current>
</sensor>
</experimental:params>
</experimental:params>-->
<!-- Joint controllers -->
<plugin
<!--<plugin
filename="ignition-gazebo-joint-position-controller-system"
name="ignition::gazebo::systems::JointPositionController">
<joint_name>horizontal_fins_joint</joint_name>
Expand Down Expand Up @@ -104,10 +104,10 @@
<joint_name>battery_joint</joint_name>
<use_velocity_commands>true</use_velocity_commands>
<cmd_max>0.0007</cmd_max>
</plugin>
</plugin>-->
<!-- Lift and drag -->
<!-- Vertical fin -->
<plugin
<!--<plugin
filename="ignition-gazebo-lift-drag-system"
name="ignition::gazebo::systems::LiftDrag">
<air_density>1000</air_density>
Expand All @@ -117,16 +117,16 @@
<cda_stall>0.03</cda_stall>
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<area>0.0244</area>-->
<!-- Link's Y is perpendicular to the control surface -->
<upward>0 1 0</upward>
<!--<upward>0 1 0</upward>-->
<!-- Link's X is pointing towards the back -->
<forward>-1 0 0</forward>
<!--<forward>-1 0 0</forward>
<link_name>vertical_fins</link_name>
<cp>0 0 0</cp>
</plugin>
</plugin>-->
<!-- Horizontal fin -->
<plugin
<!--<plugin
filename="ignition-gazebo-lift-drag-system"
name="ignition::gazebo::systems::LiftDrag">
<air_density>1000</air_density>
Expand All @@ -136,24 +136,24 @@
<cda_stall>0.03</cda_stall>
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<area>0.0244</area>-->
<!-- Link's Z is perpendicular to the control surface -->
<upward>0 0 1</upward>
<!--<upward>0 0 1</upward>-->
<!-- Link's X is pointing towards the back -->
<forward>-1 0 0</forward>
<!--<forward>-1 0 0</forward>
<link_name>horizontal_fins</link_name>
<cp>0 0 0</cp>
</plugin>
</plugin>-->
<!-- Interface with LRAUV Main Vehicle Application for each vehicle -->
<plugin
<!--<plugin
filename="TethysCommPlugin"
name="tethys::TethysCommPlugin">
<namespace>tethys</namespace>
<command_topic>tethys/command_topic</command_topic>
<state_topic>tethys/state_topic</state_topic>
<debug_printout>0</debug_printout>
</plugin>
<plugin
</plugin>-->
<!--<plugin
filename="HydrodynamicsPlugin"
name="tethys::HydrodynamicsPlugin">
<link_name>base_link</link_name>
Expand All @@ -176,23 +176,23 @@
<mQ>0</mQ>
<nRR>-632.698957</nRR>
<nR>0</nR>
</plugin>
<plugin
</plugin>-->
<!--<plugin
filename="ignition-gazebo-buoyancy-engine-system"
name="ignition::gazebo::v6::systems::BuoyancyEnginePlugin">
<link_name>buoyancy_engine</link_name>
<namespace>tethys</namespace>
<fluid_density>1000</fluid_density>
<fluid_density>1000</fluid_density>-->
<!-- 80 cc == 0.00008 m^3 -->
<min_volume>0.000080</min_volume>
<!--<min_volume>0.000080</min_volume>-->
<!-- 500 cc == 0.0005 m^3 -->
<neutral_volume>0.0005</neutral_volume>
<default_volume>0.0005</default_volume>
<!--<neutral_volume>0.0005</neutral_volume>-->
<!--<default_volume>0.0005</default_volume>-->
<!-- 955 cc == 0.000955 m^3 -->
<max_volume>0.000955</max_volume>
<!--<max_volume>0.000955</max_volume>-->
<!-- m^3/s -->
<max_inflation_rate>0.000003</max_inflation_rate>
</plugin>
<!--<max_inflation_rate>0.000003</max_inflation_rate>
</plugin>-->
<plugin
filename="ignition-gazebo-detachable-joint-system"
name="ignition::gazebo::systems::DetachableJoint">
Expand All @@ -202,7 +202,7 @@
<topic>/model/tethys/drop_weight</topic>
</plugin>

<plugin
<!--<plugin
filename="AcousticCommsPlugin"
name="tethys::AcousticCommsPlugin">
<address>1</address>
Expand All @@ -221,7 +221,7 @@
<speed_of_sound>1500</speed_of_sound>
<link_name>base_link</link_name>
<namespace>tethys</namespace>
</plugin>
</plugin>-->

</include>
</model>
Expand Down
11 changes: 2 additions & 9 deletions lrauv_ignition_plugins/worlds/buoyant_tethys.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
-->
<sdf version="1.6">
<world name="buoyant_tethys">
<gravity>0 0 -9.8</gravity>
<scene>
<!-- For turquoise ambient to match particle effect -->
<ambient>0.0 1.0 1.0</ambient>
Expand Down Expand Up @@ -53,16 +54,8 @@
<density>1</density>
</density_change>
</graded_buoyancy-->
<uniform_fluid_density>1000</uniform_fluid_density>
</plugin>

<!-- Requires ParticleEmitter2 in ign-gazebo 4.8.0, which will be copied
to ParticleEmitter in Ignition G.
See https://github.com/ignitionrobotics/ign-gazebo/pull/730 -->
<plugin
filename="ignition-gazebo-particle-emitter2-system"
name="ignition::gazebo::systems::ParticleEmitter2">
</plugin>

<!-- Uncomment for time analysis -->
<!--plugin
filename="TimeAnalysisPlugin"
Expand Down