Skip to content

Commit

Permalink
Changing values for steelhead
Browse files Browse the repository at this point in the history
  • Loading branch information
hashaam1217 committed Aug 9, 2024
1 parent 3041e49 commit db0b88a
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 15 deletions.
7 changes: 7 additions & 0 deletions src/triton_controls/config/thruster_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,13 @@
bits_per_thruster: 5
max_fwd: 3.71 # kgf
max_rev: 2.92 # kgf
t3:
contrib:
z: 1.0
lx: -0.219431
ly: -0.055
lz: 0.09

t5:
contrib:
x: -1.0
Expand Down
19 changes: 12 additions & 7 deletions src/triton_gazebo/models/triton_auv/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -29,27 +29,32 @@
</include>

<!-- Thrusters -->

<!-- Back Horizontal-->
<include>
<uri>model://triton_thruster</uri>
<pose>-0.325 0 0 1.57 0</pose>
<pose>-0.325 0 0 0 0</pose>
<name>thruster1</name>
</include>

<!-- Angled Front Left-->
<include>
<uri>model://triton_thruster</uri>
<pose>0 -0.22 0.0045 0 0 0</pose>
<pose>-0.062 -0.22 0.0045 0.785 0 0</pose>
<name>thruster2</name>
</include>

<!-- Angled Front Right-->
<include>
<uri>model://triton_thruster</uri>
<pose>-0.21 -0.33 0.0075 0 -0.785 0</pose>
<pose>0.21 -0.33 0.0075 0 -0.785 0</pose>
<name>thruster4</name>
</include>


<!-- Vertical-->
<include>
<uri>model://triton_thruster</uri>
<pose>0.21 -0.33 0.0075 0 0.785 0</pose>
<pose>-0.219431 -0.055 0.09 0 3.14 0</pose>
<name>thruster3</name>
</include>

Expand Down Expand Up @@ -83,8 +88,8 @@

<base_link>frame::frame</base_link>
<neutrally_buoyant>1</neutrally_buoyant>
<volume>0.0209673336007</volume>
<center_of_buoyancy>-0.14826 -0.1687 0.2339</center_of_buoyancy>
<volume>0.00340702866633</volume>
<center_of_buoyancy>0.1 -0.062 -0.00878</center_of_buoyancy>
<!-- <pose>-0.14826 -0.1687 0.19368 0 -0 0</pose> -->
<hydrodynamic_model>
<!-- Useful params for controls simplifications-->
Expand Down
Empty file.
17 changes: 9 additions & 8 deletions src/triton_gazebo/models/triton_frame/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,18 @@
<link name='frame'>

<!-- pose relaive to STL file origin, was moved to AUV center using Blender -->
<!-- Edited for Steelhead Mini Aug 9 2024-->
<inertial>
<mass>17.43388</mass>
<mass>29.4835</mass>
<inertia>
<ixx> 0.42659179587</ixx>
<ixy> 0.00091257391</ixy>
<ixz>-0.00613671114</ixz>
<iyy> 0.47862692534</iyy>
<iyz>-0.00224649356</iyz>
<izz> 0.42575057622</izz>
<ixx> 0.548853532</ixx>
<ixy> 0.000990367</ixy>
<ixz> 0.007434770</ixz>
<iyy> 0.725638212</iyy>
<iyz> 0.045963196</iyz>
<izz> 1.077000000</izz>
</inertia>
<pose>-0.14826 -0.1687 0.19368 0 -0 0</pose>
<pose>0.1 -0.062 -0.00878 0 -0 0</pose>
</inertial>

<!-- Visual Data -->
Expand Down

0 comments on commit db0b88a

Please sign in to comment.