-
Notifications
You must be signed in to change notification settings - Fork 267
Develop a new USV model employing a single waterjet propulsion system. #877
Description
I am currently developing a USV equipped with a single waterjet propulsion system and aim to simulate it in a manner similar to the WAM-V platform. However, since I could not find a suitable plugin for a waterjet mechanism, I instead implemented a propeller-based thruster model similar to that used in the WAM-V simulation.
I have created both the world file and the USV configuration file accordingly. The USV appears to operate logically when force and steering angle commands are applied. However, from a mathematical standpoint, I believe the model is not fully accurate. For example, the influence of the propeller installation position on the turning radius is not properly captured.
I would appreciate your advice on how to improve and optimize the simulation model so that it can better represent the physical system. This will allow me to proceed with the development of a reliable control system based on the simulated model.
Thank you very much.
<img width="850" height="554" alt="Image" src="https://github.com/user-attachments/assets/c586f850-a43b-42aa-bae4-112bbc890656" />
Code usv_dh392_roboboat_tuned.sdf
false<link name="base_link">
<inertial>
<!-- <pose>0 0 -0.05 0 0 1.57079633</pose> -->
<pose>0 0 0 0 0 1.57079633</pose>
<mass>12</mass>
<inertia>
<ixx>0.1525</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.7025</iyy>
<iyz>0.0</iyz>
<izz>0.73</izz>
</inertia>
</inertial>
<velocity_decay>
<linear>0.02</linear>
<angular>0.08</angular>
</velocity_decay>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<box><size>0.80 0.3 0.12</size></box>
</geometry>
</collision>
<visual name="visual">
<pose>0 0 0 -1.5708 0 -1.57079633</pose>
<geometry>
<mesh>
<uri>meshes/usv_base_v1.dae</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="pod_link">
<!-- <pose relative_to="base_link">0 -0.44 -0.075 0 0 1.57079633</pose> -->
<!-- -0.44 -->
<pose relative_to="base_link">-0.6 0 -0.075 0 0 0</pose>
<inertial>
<mass>0.02</mass>
<inertia>
<ixx>2.5e-4</ixx>
<iyy>2.5e-4</iyy>
<izz>2.5e-4</izz>
</inertia>
</inertial>
<!-- POD NHỎ HƠN: chỉ thay đổi kích thước ống -->
<visual name="pod_vis">
<geometry>
<cylinder>
<radius>0.008</radius>
<length>0.040</length>
</cylinder>
</geometry>
<material>
<ambient>0.15 0.15 0.15 1</ambient>
<diffuse>0.15 0.15 0.15 1</diffuse>
</material>
</visual>
<collision name="pod_col">
<geometry>
<cylinder>
<radius>0.008</radius>
<length>0.040</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- Steering joint: quay POD quanh Z để đổi hướng -->
<joint name="steering_joint" type="revolute">
<parent>base_link</parent>
<child>pod_link</child>
<pose relative_to="">-0.6 0 -0.075 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-0.61</lower> <!-- -35° -->
<upper>0.61</upper> <!-- +35° -->
<effort>5.0</effort>
<velocity>6.0</velocity>
</limit>
<dynamics>
<damping>0.05</damping>
<friction>0.01</friction>
</dynamics>
</axis>
</joint>
<!-- PROP: cánh quạt (quay RPM quanh trục Y) -->
<link name="prop_link">
<!-- Trùng đúng vị trí POD (không bù trừ thêm), để joint đặt đúng tâm -->
<pose relative_to="pod_link">0 0 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>1e-5</ixx><iyy>2e-5</iyy><izz>2e-5</izz>
</inertia>
</inertial>
<!-- propeller.dae: trục mặc định theo Z, xoay ROLL +90° để trục quay trùng Y -->
<visual name="propeller_visual">
<geometry>
<mesh>
<uri>meshes/propeller.dae</uri>
<scale>0.08 0.08 0.08</scale>
</mesh>
</geometry>
<pose>0 0 0 1.57079632679 0 0</pose>
</visual>
<collision name="prop_collision">
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
<pose>0 0 0 1.57079632679 0 0</pose>
</collision>
</link>
<!-- Spin joint: quay PROP quanh trục Y để tạo lực đẩy -->
<joint name="prop_spin_joint" type="revolute">
<parent>pod_link</parent>
<child>prop_link</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1e4</lower> <!-- không cần vô cực -->
<upper> 1e4</upper>
<effort>1.0</effort> <!-- nhỏ lại để tránh xung lực -->
<velocity>300</velocity> <!-- cap tốc độ -->
</limit>
<dynamics>
<damping>0.01</damping> <!-- từ 1e-4 -> 0.01 -->
<friction>0.0</friction>
</dynamics>
</axis>
</joint>
<!-- === END: POD + PROP === -->
<!-- Controller góc lái (position) -->
<plugin filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>steering_joint</joint_name>
<p_gain>12.0</p_gain>
<i_gain>0.0</i_gain>
<d_gain>0.6</d_gain>
<i_max>0.0</i_max>
<i_min>0.0</i_min>
<cmd_limit>1.04719755</cmd_limit> <!-- |yaw| <= 90° -->
<force>35.0</force>
</plugin>
<!-- Điều khiển vận tốc cho prop: GIỐNG CÁCH WAM-V RA LỆNH /cmd_vel -->
<plugin filename="gz-sim-joint-controller-system"
name="gz::sim::systems::JointController">
<joint_name>prop_spin_joint</joint_name>
<command_interface>velocity</command_interface>
<use_force>true</use_force>
<pid>
<p>0.2</p><i>0.0</i><d>0.0</d><i_clamp>0.0</i_clamp>
</pid>
<max_force>0.6</max_force> <!-- tăng lực tối đa một chút để USV “bốc” hơn -->
</plugin>
<plugin filename="libSimpleThruster.so" name="SimpleThruster">
<link_name>pod_link</link_name>
<cmd_topic>/usv/thrust_cmd</cmd_topic>
<thrust_gain>35.0</thrust_gain>
<drag_gain>0.02</drag_gain>
<thrust_direction>1 0 0</thrust_direction>
</plugin>
<!-- <plugin filename="libSurface.so"
name="maritime::Surface"> -->
<plugin filename="libSurface.so" name="vrx::Surface">
<link_name>base_link</link_name>
<hull_length>0.8</hull_length>
<hull_radius>0.060</hull_radius>
<fluid_level>0.0</fluid_level>
<fluid_density>1000</fluid_density>
<points>
<point> 0.38 0.12 -0.03</point>
<point>-0.38 0.12 -0.03</point>
</points>
<wavefield><topic>/vrx/wavefield/parameters</topic></wavefield>
<!-- <wavefield><topic>/gazebo/wavefield/parameters</topic></wavefield> -->
</plugin>
<!-- <plugin filename="libSurface.so"
name="maritime::Surface"> -->
<plugin filename="libSurface.so" name="vrx::Surface">
<link_name>base_link</link_name>
<hull_length>0.8</hull_length>
<hull_radius>0.060</hull_radius>
<fluid_level>0.0</fluid_level>
<fluid_density>1000</fluid_density>
<points>
<point> 0.38 -0.12 -0.03</point>
<point>-0.38 -0.12 -0.03</point>
</points>
<wavefield><topic>/vrx/wavefield/parameters</topic></wavefield>
<!-- <wavefield><topic>/gazebo/wavefield/parameters</topic></wavefield> -->
</plugin>
<plugin filename="libSurface.so" name="vrx::Surface">
<!-- <plugin filename="libSurface.so"
name="maritime::Surface"> -->
<link_name>base_link</link_name>
<hull_length>0.8</hull_length>
<hull_radius>0.060</hull_radius>
<fluid_level>0.0</fluid_level>
<fluid_density>1000</fluid_density>
<points>
<point> 0.38 0.00 -0.03</point>
<point>-0.38 0.00 -0.03</point>
</points>
<wavefield><topic>/vrx/wavefield/parameters</topic></wavefield>
<!-- <wavefield><topic>/gazebo/wavefield/parameters</topic></wavefield> -->
</plugin>
<!-- <plugin filename="libSurface.so"
name="maritime::Surface">
<link_name>base_link</link_name>
<hull_length>0.8</hull_length>
<hull_radius>0.067</hull_radius>
<fluid_level>0.0</fluid_level>
<fluid_density>1000</fluid_density>
<points>
<point> 0.38 0.06 -0.03</point>
<point>-0.38 0.06 -0.03</point>
</points>
<wavefield><topic>/gazebo/wavefield/parameters</topic></wavefield>
</plugin>
<plugin filename="libSurface.so"
name="maritime::Surface">
<link_name>base_link</link_name>
<hull_length>0.8</hull_length>
<hull_radius>0.067</hull_radius>
<fluid_level>0.0</fluid_level>
<fluid_density>1000</fluid_density>
<points>
<point> 0.38 -0.06 -0.03</point>
<point>-0.38 -0.06 -0.03</point>
</points>
<wavefield><topic>/gazebo/wavefield/parameters</topic></wavefield>
</plugin> -->
<!-- Damping thủy lực cơ bản (không chồng với gz-sim-hydrodynamics-system) -->
<plugin filename="libSimpleHydrodynamics.so" name="vrx::SimpleHydrodynamics">
<link_name>base_link</link_name>
<xDotU>0.4</xDotU>
<yDotV>1.8</yDotV>
<!-- <yDotV>0.8</yDotV> -->
<nDotR>0.05</nDotR>
<!-- <nDotR>0.02</nDotR> -->
<xU>4.0</xU>
<yV>12.0</yV>
<!-- <yV>6.0</yV> -->
<zW>12.0</zW>
<kP>10.0</kP>
<mQ>12.0</mQ>
<nR>80.0</nR>
<!-- <nR>40.0</nR> -->
<xUU>10.0</xUU>
<yVV>30.0</yVV>
<kPP>12.0</kPP>
<mQQ>16.0</mQQ>
<nRR>150.0</nRR>
<!-- <nRR>80.0</nRR> -->
</plugin>
<!-- <plugin filename="libLiftDrag.so" name="usv_liftdrag">
<link_name>base_link</link_name>
<air_density>1.225</air_density>
<area>0.2</area>
<cla>0.0</cla>
<cda>1.0</cda>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<cp>0 0 0.1</cp>
</plugin> -->
<physics name="fast" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
<ode>
<solver>
<type>quick</type> <!-- PGS -->
<iters>200</iters>
<sor>1.3</sor>
</solver>
<constraints>
<cfm>1e-6</cfm>
<erp>0.2</erp>
<contact_max_correcting_vel>5.0</contact_max_correcting_vel>
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
</physics>
<!-- Bảo đảm có trọng lực -->
<gravity>0 0 -9.81</gravity>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.8 0.8 0.8 1</background>
<!-- <engine>ogre2</engine> -->
<sky>
<clouds>
<speed>0.6</speed>
<direction>0.0</direction>
<humidity>0.5</humidity>
<mean_size>1</mean_size>
</clouds>
</sky>
<grid>false</grid>
<shadows>true</shadows>
</scene>
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics"></plugin>
<plugin filename="gz-sim-user-commands-system" name="gz::sim::systems::UserCommands"></plugin>
<plugin filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster"></plugin>
<!-- <light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<linear>0.01</linear>
<constant>0.9</constant>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light> -->
<model name="pool">
<static>true</static>
<pose>0 0 0 0 0 0</pose>
<!-- Bottom -->
<link name="bottom">
<pose>0 0 -2.05 0 0 0</pose>
<collision name="bottom_collision">
<geometry>
<box>
<size>50 25 0.1</size>
</box>
</geometry>
</collision>
<visual name="bottom_visual">
<geometry>
<box>
<size>50 25 0.1</size>
</box>
</geometry>
<material>
<ambient>0.5 0.5 0.5 1</ambient>
<diffuse>0.5 0.5 0.5 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
</material>
</visual>
</link>
<!-- North wall -->
<link name="north_wall">
<pose>0 12.5 -1.1 0 0 0</pose>
<collision name="north_collision">
<geometry>
<box>
<size>50 0.5 2.2</size>
</box>
</geometry>
</collision>
<visual name="north_visual">
<geometry>
<box>
<size>50 0.5 2.2</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.3 0.3 0.3 1</diffuse>
<specular>0.3 0.3 0.3 1</specular>
</material>
</visual>
</link>
<!-- South wall -->
<link name="south_wall">
<pose>0 -12.5 -1.1 0 0 0</pose>
<collision name="south_collision">
<geometry>
<box>
<size>50 0.5 2.2</size>
</box>
</geometry>
</collision>
<visual name="south_visual">
<geometry>
<box>
<size>50 0.5 2.2</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.3 0.3 0.3 1</diffuse>
<specular>0.3 0.3 0.3 1</specular>
</material>
</visual>
</link>
<!-- East wall -->
<link name="east_wall">
<pose>25 0 -1.1 0 0 1.57</pose>
<collision name="east_collision">
<geometry>
<box>
<size>25 0.5 2.2</size>
</box>
</geometry>
</collision>
<visual name="east_visual">
<geometry>
<box>
<size>25 0.5 2.2</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.3 0.3 0.3 1</diffuse>
<specular>0.3 0.3 0.3 1</specular>
</material>
</visual>
</link>
<!-- West wall -->
<link name="west_wall">
<pose>-25 0 -1.1 0 0 1.57</pose>
<collision name="west_collision">
<geometry>
<box>
<size>25 0.5 2.2</size>
</box>
</geometry>
</collision>
<visual name="west_visual">
<geometry>
<box>
<size>25 0.5 2.2</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.3 0.3 0.3 1</diffuse>
<specular>0.3 0.3 0.3 1</specular>
</material>
</visual>
</link>
<!-- Water visual (no collision, just visual) -->
<link name="water">
<pose>0 0 -1.01 0 0 0</pose>
<visual name="water_visual">
<geometry>
<box>
<size>50 25 2</size> <!-- Thin layer -->
</box>
</geometry>
<material>
<ambient>0.0 0.5 0.8 0.75</ambient>
<diffuse>0.0 0.5 0.8 0.75</diffuse>
<specular>0.0 0.5 0.8 0.75</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<!-- <plugin filename="gz-sim-buoyancy-system" name="gz::sim::systems::Buoyancy">
<graded_buoyancy>
<default_density>1000</default_density>
<density_change>
<above_depth>0.0</above_depth>
<density>1.0</density>
</density_change>
</graded_buoyancy>
<link>
<name>usv_dh392::base_link</name>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box><size>0.8 0.3 0.25</size></box>
</geometry>
<center_of_buoyancy>0 0 0.03</center_of_buoyancy>
</link>
</plugin> -->
<!-- Plugin cho sóng (từ sydney_regatta.sdf) -->
<plugin filename="libPublisherPlugin.so" name="vrx::PublisherPlugin">
<message type="gz.msgs.Param" topic="/vrx/wavefield/parameters" every="2.0">
params { key: "direction" value { type: DOUBLE double_value: 0.0 } }
params { key: "amplitude" value { type: DOUBLE double_value: 0.0} }
params { key: "period" value { type: DOUBLE double_value: 2.0 } }
params { key: "steepness" value { type: DOUBLE double_value: 0.14 } }
</message>
</plugin>
<!-- ADDED: Gió -->
<plugin filename="libUSVWind.so" name="vrx::USVWind">
<wind_obj>
<name>usv_dh392</name>
<link_name>usv_dh392::base_link</link_name>
<coeff_vector>0.6 0.8 0.005</coeff_vector>
</wind_obj>
<wind_direction>0.0</wind_direction>
<wind_mean_velocity>0.0</wind_mean_velocity>
<var_wind_gain_constants>0.0</var_wind_gain_constants>
<var_wind_time_constants>2.0</var_wind_time_constants>
<random_seed>10</random_seed>
<update_rate>10</update_rate>
<topic_wind_speed>/vrx/debug/wind/speed</topic_wind_speed>
<topic_wind_direction>/vrx/debug/wind/direction</topic_wind_direction>
</plugin>
<!-- <include>
<name>Coast Waves</name>
<pose>0 0 0 0 0 0</pose>
<uri>coast_waves</uri>
</include> -->
<include>
<name>usv_dh392</name>
<uri>file:///home/ducduy392/vrx_ws/src/vrx/vrx_gz/models/usv_dh392_model/usv_dh392_roboboat_tuned.sdf</uri>
<!-- <pose>0 0 0.01 0 0 0</pose> -->
<pose>0 0 0.01 0 0 1.57079633</pose>
</include>