Skip to content

Commit 76bc663

Browse files
Reverse specific motors for some reason
1 parent b63f681 commit 76bc663

File tree

2 files changed

+25
-17
lines changed

2 files changed

+25
-17
lines changed

src/surface/rov_gazebo/config/sub.parm

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ SERVO16_TRIM 1500
3939
SERVO1_FUNCTION 33
4040
SERVO1_MAX 1900
4141
SERVO1_MIN 1100
42-
SERVO1_REVERSED 1
42+
SERVO1_REVERSED 0
4343
SERVO1_TRIM 1500
4444
SERVO2_FUNCTION 34
4545
SERVO2_MAX 1900
@@ -54,7 +54,7 @@ SERVO3_TRIM 1500
5454
SERVO4_FUNCTION 36
5555
SERVO4_MAX 1900
5656
SERVO4_MIN 1100
57-
SERVO4_REVERSED 1
57+
SERVO4_REVERSED 0
5858
SERVO4_TRIM 1500
5959
SERVO5_FUNCTION 37
6060
SERVO5_MAX 1900
@@ -69,7 +69,7 @@ SERVO6_TRIM 1500
6969
SERVO7_FUNCTION 39
7070
SERVO7_MAX 1900
7171
SERVO7_MIN 1100
72-
SERVO7_REVERSED 1
72+
SERVO7_REVERSED 0
7373
SERVO7_TRIM 1500
7474
SERVO8_FUNCTION 40
7575
SERVO8_MAX 1900
@@ -82,6 +82,14 @@ SERVO9_MIN 1100
8282
SERVO9_REVERSED 0
8383
SERVO9_TRIM 1500
8484

85+
MOT_1_DIRECTION 1
86+
MOT_2_DIRECTION -1
87+
MOT_3_DIRECTION 1
88+
MOT_4_DIRECTION -1
89+
MOT_5_DIRECTION 1
90+
MOT_7_DIRECTION 1
91+
MOT_6_DIRECTION 1
92+
MOT_8_DIRECTION 1
8593

8694
# These settings were copied from ardupilot/Tools/autotest/default_params/sub.parm
8795
BATT_MONITOR 4

src/surface/rov_gazebo/models/rov24/model.sdf

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@
164164
<pose>0 0 0 -1.571 0 0</pose>
165165
<geometry>
166166
<mesh>
167-
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
167+
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
168168
</mesh>
169169
</geometry>
170170
</visual>
@@ -182,7 +182,7 @@
182182
</link>
183183

184184
<link name="thruster2">
185-
<pose>0.1848 0.2104 0.1651 -1.571 1.571 -2.269</pose>
185+
<pose>0.1848 0.2104 0.1651 1.571 1.571 -2.269</pose>
186186
<visual name="thruster_prop_visual">
187187
<pose>0 0 0 -1.571 0 0</pose>
188188
<geometry>
@@ -228,7 +228,7 @@
228228
</link>
229229

230230
<link name="thruster4">
231-
<pose>-0.1848 0.2104 0.1651 -1.571 1.571 2.269</pose>
231+
<pose>-0.1848 0.2104 0.1651 1.571 1.571 2.269</pose>
232232
<visual name="thruster_prop_visual">
233233
<pose>0 0 0 1.571 0 0</pose>
234234
<geometry>
@@ -251,12 +251,12 @@
251251
</link>
252252

253253
<link name="thruster5">
254-
<pose>0.0985 -0.2408 0.0577 3.141 0 0</pose>
254+
<pose>0.0985 -0.2408 0.0577 0 0 0</pose>
255255
<visual name="thruster_prop_visual">
256256
<pose>0 0 0 -1.571 0 1.571</pose>
257257
<geometry>
258258
<mesh>
259-
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
259+
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
260260
</mesh>
261261
</geometry>
262262
</visual>
@@ -274,12 +274,12 @@
274274
</link>
275275

276276
<link name="thruster6">
277-
<pose>0.0985 0.2408 0.0577 3.141 0 0</pose>
277+
<pose>0.0985 0.2408 0.0577 0 0 0</pose>
278278
<visual name="thruster_prop_visual">
279279
<pose>0 0 0 1.571 0 1.571</pose>
280280
<geometry>
281281
<mesh>
282-
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
282+
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
283283
</mesh>
284284
</geometry>
285285
</visual>
@@ -297,12 +297,12 @@
297297
</link>
298298

299299
<link name="thruster7">
300-
<pose>-0.0985 -0.2408 0.0577 3.141 0 0</pose>
300+
<pose>-0.0985 -0.2408 0.0577 0 0 0</pose>
301301
<visual name="thruster_prop_visual">
302302
<pose>0 0 0 1.571 0 1.571</pose>
303303
<geometry>
304304
<mesh>
305-
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
305+
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
306306
</mesh>
307307
</geometry>
308308
</visual>
@@ -320,12 +320,12 @@
320320
</link>
321321

322322
<link name="thruster8">
323-
<pose>-0.0985 0.2408 0.0577 3.141 0 0</pose>
323+
<pose>-0.0985 0.2408 0.0577 0 0 0</pose>
324324
<visual name="thruster_prop_visual">
325325
<pose>0 0 0 -1.571 0 1.571</pose>
326326
<geometry>
327327
<mesh>
328-
<uri>model://rov24/meshes/t200_cw_prop.dae</uri>
328+
<uri>model://rov24/meshes/t200_ccw_prop.dae</uri>
329329
</mesh>
330330
</geometry>
331331
</visual>
@@ -425,7 +425,8 @@
425425
name="gz::sim::systems::Thruster">
426426
<namespace>rov24</namespace>
427427
<joint_name>thruster2_joint</joint_name>
428-
<thrust_coefficient>0.02</thrust_coefficient>
428+
<!-- Reverse spin to balance torque -->
429+
<thrust_coefficient>-0.02</thrust_coefficient>
429430
<max_thrust_cmd>36.4</max_thrust_cmd>
430431
<min_thrust_cmd>-28.6</min_thrust_cmd>
431432
<fluid_density>1000.0</fluid_density>
@@ -454,8 +455,7 @@
454455
name="gz::sim::systems::Thruster">
455456
<namespace>rov24</namespace>
456457
<joint_name>thruster4_joint</joint_name>
457-
<!-- Reverse spin to balance torque -->
458-
<thrust_coefficient>-0.02</thrust_coefficient>
458+
<thrust_coefficient>0.02</thrust_coefficient>
459459
<max_thrust_cmd>36.4</max_thrust_cmd>
460460
<min_thrust_cmd>-28.6</min_thrust_cmd>
461461
<fluid_density>1000.0</fluid_density>

0 commit comments

Comments
 (0)