|
164 | 164 | <pose>0 0 0 -1.571 0 0</pose> |
165 | 165 | <geometry> |
166 | 166 | <mesh> |
167 | | - <uri>model://rov24/meshes/t200_cw_prop.dae</uri> |
| 167 | + <uri>model://rov24/meshes/t200_ccw_prop.dae</uri> |
168 | 168 | </mesh> |
169 | 169 | </geometry> |
170 | 170 | </visual> |
|
182 | 182 | </link> |
183 | 183 |
|
184 | 184 | <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> |
186 | 186 | <visual name="thruster_prop_visual"> |
187 | 187 | <pose>0 0 0 -1.571 0 0</pose> |
188 | 188 | <geometry> |
|
228 | 228 | </link> |
229 | 229 |
|
230 | 230 | <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> |
232 | 232 | <visual name="thruster_prop_visual"> |
233 | 233 | <pose>0 0 0 1.571 0 0</pose> |
234 | 234 | <geometry> |
|
251 | 251 | </link> |
252 | 252 |
|
253 | 253 | <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> |
255 | 255 | <visual name="thruster_prop_visual"> |
256 | 256 | <pose>0 0 0 -1.571 0 1.571</pose> |
257 | 257 | <geometry> |
258 | 258 | <mesh> |
259 | | - <uri>model://rov24/meshes/t200_cw_prop.dae</uri> |
| 259 | + <uri>model://rov24/meshes/t200_ccw_prop.dae</uri> |
260 | 260 | </mesh> |
261 | 261 | </geometry> |
262 | 262 | </visual> |
|
274 | 274 | </link> |
275 | 275 |
|
276 | 276 | <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> |
278 | 278 | <visual name="thruster_prop_visual"> |
279 | 279 | <pose>0 0 0 1.571 0 1.571</pose> |
280 | 280 | <geometry> |
281 | 281 | <mesh> |
282 | | - <uri>model://rov24/meshes/t200_ccw_prop.dae</uri> |
| 282 | + <uri>model://rov24/meshes/t200_cw_prop.dae</uri> |
283 | 283 | </mesh> |
284 | 284 | </geometry> |
285 | 285 | </visual> |
|
297 | 297 | </link> |
298 | 298 |
|
299 | 299 | <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> |
301 | 301 | <visual name="thruster_prop_visual"> |
302 | 302 | <pose>0 0 0 1.571 0 1.571</pose> |
303 | 303 | <geometry> |
304 | 304 | <mesh> |
305 | | - <uri>model://rov24/meshes/t200_ccw_prop.dae</uri> |
| 305 | + <uri>model://rov24/meshes/t200_cw_prop.dae</uri> |
306 | 306 | </mesh> |
307 | 307 | </geometry> |
308 | 308 | </visual> |
|
320 | 320 | </link> |
321 | 321 |
|
322 | 322 | <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> |
324 | 324 | <visual name="thruster_prop_visual"> |
325 | 325 | <pose>0 0 0 -1.571 0 1.571</pose> |
326 | 326 | <geometry> |
327 | 327 | <mesh> |
328 | | - <uri>model://rov24/meshes/t200_cw_prop.dae</uri> |
| 328 | + <uri>model://rov24/meshes/t200_ccw_prop.dae</uri> |
329 | 329 | </mesh> |
330 | 330 | </geometry> |
331 | 331 | </visual> |
|
425 | 425 | name="gz::sim::systems::Thruster"> |
426 | 426 | <namespace>rov24</namespace> |
427 | 427 | <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> |
429 | 430 | <max_thrust_cmd>36.4</max_thrust_cmd> |
430 | 431 | <min_thrust_cmd>-28.6</min_thrust_cmd> |
431 | 432 | <fluid_density>1000.0</fluid_density> |
|
454 | 455 | name="gz::sim::systems::Thruster"> |
455 | 456 | <namespace>rov24</namespace> |
456 | 457 | <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> |
459 | 459 | <max_thrust_cmd>36.4</max_thrust_cmd> |
460 | 460 | <min_thrust_cmd>-28.6</min_thrust_cmd> |
461 | 461 | <fluid_density>1000.0</fluid_density> |
|
0 commit comments