Skip to content

Commit 55f510e

Browse files
committed
Added very basic thusters
1 parent 83bee84 commit 55f510e

File tree

1 file changed

+74
-0
lines changed

1 file changed

+74
-0
lines changed

ros_ws/src/navigation/config/karaburan_boat.sdf

Lines changed: 74 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,80 @@
3232
</velocity_decay>
3333
</link>
3434

35+
<!-- LEFT PROPELLER (link + joint) -->
36+
<link name="left_prop">
37+
<inertial>
38+
<pose>0 0 0 0 0 0</pose>
39+
<mass>0.05</mass>
40+
<inertia>
41+
<ixx>1e-5</ixx><iyy>1e-5</iyy><izz>1e-5</izz>
42+
<ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
43+
</inertia>
44+
</inertial>
45+
<visual name="left_prop_vis">
46+
<geometry><cylinder><radius>0.04</radius><length>0.02</length></cylinder></geometry>
47+
<!-- achter de romp (x<0), bakboord (y>0), op halve hoogte z=0.10 -->
48+
<pose>-0.35 0.18 0.10 0 0 0</pose>
49+
</visual>
50+
<!-- GEEN collision -> geen extra drijfkracht -->
51+
</link>
52+
53+
<joint name="left_prop_joint" type="revolute">
54+
<parent>hull</parent>
55+
<child>left_prop</child>
56+
<!-- as = +X in child-frame: “vooruit” is +thrust -->
57+
<pose>-0.35 0.18 0.10 0 0 0</pose>
58+
<axis>
59+
<xyz>1 0 0</xyz>
60+
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
61+
</axis>
62+
</joint>
63+
64+
<!-- RIGHT PROPELLER -->
65+
<link name="right_prop">
66+
<inertial>
67+
<pose>0 0 0 0 0 0</pose>
68+
<mass>0.05</mass>
69+
<inertia>
70+
<ixx>1e-5</ixx><iyy>1e-5</iyy><izz>1e-5</izz>
71+
<ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
72+
</inertia>
73+
</inertial>
74+
<visual name="right_prop_vis">
75+
<geometry><cylinder><radius>0.04</radius><length>0.02</length></cylinder></geometry>
76+
<pose>-0.35 -0.18 0.10 0 0 0</pose>
77+
</visual>
78+
</link>
79+
80+
<joint name="right_prop_joint" type="revolute">
81+
<parent>hull</parent>
82+
<child>right_prop</child>
83+
<pose>-0.35 -0.18 0.10 0 0 0</pose>
84+
<axis>
85+
<xyz>1 0 0</xyz>
86+
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
87+
</axis>
88+
</joint>
89+
90+
<!-- Thruster plugins: 1 per joint -->
91+
<plugin filename="gz-sim-thruster-system" name="gz::sim::systems::Thruster">
92+
<namespace>karaburan</namespace>
93+
<joint_name>left_prop_joint</joint_name>
94+
<fluid_density>1000</fluid_density>
95+
<propeller_diameter>0.08</propeller_diameter>
96+
<thrust_coefficient>0.004</thrust_coefficient>
97+
<!-- standaard: cmd_thrust (N), joint wordt visueel gesponnen -->
98+
</plugin>
99+
100+
<plugin filename="gz-sim-thruster-system" name="gz::sim::systems::Thruster">
101+
<namespace>karaburan</namespace>
102+
<joint_name>right_prop_joint</joint_name>
103+
<fluid_density>1000</fluid_density>
104+
<propeller_diameter>0.08</propeller_diameter>
105+
<thrust_coefficient>0.004</thrust_coefficient>
106+
</plugin>
107+
108+
35109
<plugin name="gz::sim::systems::Hydrodynamics" filename="gz-sim-hydrodynamics-system">
36110
<link_name>hull</link_name>
37111
<water_density>998</water_density>

0 commit comments

Comments
 (0)