Skip to content

Commit

Permalink
Reverse specific motors for some reason
Browse files Browse the repository at this point in the history
  • Loading branch information
NoahMollerstuen committed Sep 17, 2024
1 parent b63f681 commit 76bc663
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 17 deletions.
14 changes: 11 additions & 3 deletions src/surface/rov_gazebo/config/sub.parm
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ SERVO16_TRIM 1500
SERVO1_FUNCTION 33
SERVO1_MAX 1900
SERVO1_MIN 1100
SERVO1_REVERSED 1
SERVO1_REVERSED 0
SERVO1_TRIM 1500
SERVO2_FUNCTION 34
SERVO2_MAX 1900
Expand All @@ -54,7 +54,7 @@ SERVO3_TRIM 1500
SERVO4_FUNCTION 36
SERVO4_MAX 1900
SERVO4_MIN 1100
SERVO4_REVERSED 1
SERVO4_REVERSED 0
SERVO4_TRIM 1500
SERVO5_FUNCTION 37
SERVO5_MAX 1900
Expand All @@ -69,7 +69,7 @@ SERVO6_TRIM 1500
SERVO7_FUNCTION 39
SERVO7_MAX 1900
SERVO7_MIN 1100
SERVO7_REVERSED 1
SERVO7_REVERSED 0
SERVO7_TRIM 1500
SERVO8_FUNCTION 40
SERVO8_MAX 1900
Expand All @@ -82,6 +82,14 @@ SERVO9_MIN 1100
SERVO9_REVERSED 0
SERVO9_TRIM 1500

MOT_1_DIRECTION 1
MOT_2_DIRECTION -1
MOT_3_DIRECTION 1
MOT_4_DIRECTION -1
MOT_5_DIRECTION 1
MOT_7_DIRECTION 1
MOT_6_DIRECTION 1
MOT_8_DIRECTION 1

# These settings were copied from ardupilot/Tools/autotest/default_params/sub.parm
BATT_MONITOR 4
Expand Down
28 changes: 14 additions & 14 deletions src/surface/rov_gazebo/models/rov24/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@
<pose>0 0 0 -1.571 0 0</pose>
<geometry>
<mesh>
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
</mesh>
</geometry>
</visual>
Expand All @@ -182,7 +182,7 @@
</link>

<link name="thruster2">
<pose>0.1848 0.2104 0.1651 -1.571 1.571 -2.269</pose>
<pose>0.1848 0.2104 0.1651 1.571 1.571 -2.269</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 -1.571 0 0</pose>
<geometry>
Expand Down Expand Up @@ -228,7 +228,7 @@
</link>

<link name="thruster4">
<pose>-0.1848 0.2104 0.1651 -1.571 1.571 2.269</pose>
<pose>-0.1848 0.2104 0.1651 1.571 1.571 2.269</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 1.571 0 0</pose>
<geometry>
Expand All @@ -251,12 +251,12 @@
</link>

<link name="thruster5">
<pose>0.0985 -0.2408 0.0577 3.141 0 0</pose>
<pose>0.0985 -0.2408 0.0577 0 0 0</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 -1.571 0 1.571</pose>
<geometry>
<mesh>
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
</mesh>
</geometry>
</visual>
Expand All @@ -274,12 +274,12 @@
</link>

<link name="thruster6">
<pose>0.0985 0.2408 0.0577 3.141 0 0</pose>
<pose>0.0985 0.2408 0.0577 0 0 0</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 1.571 0 1.571</pose>
<geometry>
<mesh>
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
</mesh>
</geometry>
</visual>
Expand All @@ -297,12 +297,12 @@
</link>

<link name="thruster7">
<pose>-0.0985 -0.2408 0.0577 3.141 0 0</pose>
<pose>-0.0985 -0.2408 0.0577 0 0 0</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 1.571 0 1.571</pose>
<geometry>
<mesh>
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
</mesh>
</geometry>
</visual>
Expand All @@ -320,12 +320,12 @@
</link>

<link name="thruster8">
<pose>-0.0985 0.2408 0.0577 3.141 0 0</pose>
<pose>-0.0985 0.2408 0.0577 0 0 0</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 -1.571 0 1.571</pose>
<geometry>
<mesh>
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
</mesh>
</geometry>
</visual>
Expand Down Expand Up @@ -425,7 +425,8 @@
name="gz::sim::systems::Thruster">
<namespace>rov24</namespace>
<joint_name>thruster2_joint</joint_name>
<thrust_coefficient>0.02</thrust_coefficient>
<!-- Reverse spin to balance torque -->
<thrust_coefficient>-0.02</thrust_coefficient>
<max_thrust_cmd>36.4</max_thrust_cmd>
<min_thrust_cmd>-28.6</min_thrust_cmd>
<fluid_density>1000.0</fluid_density>
Expand Down Expand Up @@ -454,8 +455,7 @@
name="gz::sim::systems::Thruster">
<namespace>rov24</namespace>
<joint_name>thruster4_joint</joint_name>
<!-- Reverse spin to balance torque -->
<thrust_coefficient>-0.02</thrust_coefficient>
<thrust_coefficient>0.02</thrust_coefficient>
<max_thrust_cmd>36.4</max_thrust_cmd>
<min_thrust_cmd>-28.6</min_thrust_cmd>
<fluid_density>1000.0</fluid_density>
Expand Down

0 comments on commit 76bc663

Please sign in to comment.