Open gaobo9109 opened 6 years ago
Hi @gaobo9109, the parameter structure for the plugin you are using is thought to be for the underwater vehicles. There is a script that you can use to generate the robot description package for a new vehicle, you can check this here. For surface vessels there is the option to add these parameters
<metacentric_width>0.4</metacentric_width>
<metacentric_length>0.4</metacentric_length>
<water_level_plane_area>0.48</water_level_plane_area>
so that the buoyancy force is calculated using the simple boxed-shaped surface vessel model (you can check these slides on Fossen's lecture notes to see the description of the model.
I have done some tests using Clearpath Robotics' Kingfisher, the same model used by the usv_gazebo_plugins
from Brian Bingham, to check if the plugin was running. I rewrote the parameters for the plugins from this package, maybe you can use them as a reference to start your model.
<xacro:property name="cob" value="0.0 0.0 0.0"/>
<xacro:property name="volume" value="1.0"/>
<xacro:property name="width" value="1.0"/>
<xacro:property name="length" value="1.35"/>
<xacro:property name="height" value="0.324261"/>
<xacro:macro name="kingfisher_hydro_model" params="namespace">
<link name="${namespace}/base_link">
<neutrally_buoyant>0</neutrally_buoyant>
<volume>${volume}</volume>
<box>
<width>${width}</width>
<length>${length}</length>
<height>${height}</height>
</box>
<center_of_buoyancy>${cob}</center_of_buoyancy>
<!-- The buoyancy plugin in the UUV Simulator can then be adapted
to receive the additional parameters used to describe the
buoyancy force computation for the surface vessel.
-->
<metacentric_width>0.4</metacentric_width>
<metacentric_length>0.4</metacentric_length>
<water_level_plane_area>0.48</water_level_plane_area>
<hydrodynamic_model>
<type>fossen</type>
<added_mass>
5 0 0 0 0 0
0 5 0 0 0 0
0 0 0.1 0 0 0
0 0 0 0.1 0 0
0 0 0 0 0.1 0
0 0 0 0 0 1
</added_mass>
<linear_damping>
-20 -20 -20 -20 -20 -20
</linear_damping>
<quadratic_damping>
-10.0 -10.0 -10.0 -50.0 -50.0 -50.0
</quadratic_damping>
</hydrodynamic_model>
</link>
</xacro:macro>
Could you tell me which Gazebo version are you using? This issue #166 showed similar problems, but I am running Gazebo 7.8 here and haven't seen this happening. If you have any more questions, let me know.
Thanks for the help. I am using gazebo version 7.00.
If you don't mind, I have a few more questions regarding the parameters in the plugin. Firstly, what exactly is the metacentric width and metacentric length? I looked through Fossen's lecture slide and it only mentions metacentric height. Is it okay to stick to the same parameter value if I am modelling WAM-V (wave adaptive modular vessel). Secondly, how do you determine the values for added mass, linear damping and quadratic damping?
Your help would be much appreciated.
Hi, I tried the following parameters to model the WAM-V
mass: 150 volumn: 1 box width: 2.44 box length: 3.91 box height: 1.27 center_of_buoyancy: 0 0 0 metacentric_width: 0.4 metacentric_length: 0.4 water_level_plane_area: 1.1
The other parameters I copied from your previous post.
In order for the buoyant force to be equal the mass, submerged height only needs to be 0.133m, since water_level_plane_area density of water submerged_height = mass. However, my model is still mostly submerged in water.
I think I found a bug in BuoyancyObject.cc.
if (z + height / 2.0 > 0.5)
{
// Vessel is completely out of the water
buoyancyForce = math::Vector3(0, 0, 0);
buoyancyTorque = math::Vector3(0, 0, 0);
// Store the restoring force vector, if needed
this->StoreVector(RESTORING_FORCE, buoyancyForce);
return;
}
else if (z + height / 2.0 < 0)
{
this->submergedHeight = this->boundingBox.GetZLength();
}
else
{
this->submergedHeight = this->boundingBox.GetZLength() / 2 - z;
}
I think the line (z + height / 2.0 > 0.5) should be (z + height / 2.0 > height). If not, for really tall model, buoyancy force would not applied even when the model is in contact with the water. For example, if the model bounding box height is 2, and starting pose.z is 0, then this condition is fulfilled even though the object is partially submerged.
Hi @gaobo9109, thanks for spotting this. I will check on how to improve this. :)
Hi, I am unable to make my model move properly when using the VelocityControl and AccelerationControl code. I suspect it is because my model inertia matrix is not configured properly, or the placement of thrusters is not done properly. Is it possible for you to send me the urdf file you use to test the Kingfisher model? Thanks.
Hi, unfortunately I can't share them here because since it contains meshes with a brand name it has to go through internal clearing first. I can share the URDF files I have made though and describe how to set the meshes from the official kingfisher repository yourself. Would that work for you? Sorry for the delay on answering.
Hi, Which simulator I can use for Autonomous Surface Vessels. Can you suggest me better simulator for path planning and collision avoidance?
@musamarcusso Hi, would you be able to share the URDF files you've made and describe how the meshes are set? I am also trying to add a usv model and it would be very helpful. Thanks
Please take a look at https://github.com/disaster-robotics-proalertas/usv_sim_lsa which has lots of feature for USV/ASV simulation, including models of boats and wind/water current models. In the near feature there will be COLREG compliance collision avoidance and coverage path planning.
On Tue, Jul 2, 2019 at 10:32 AM Ramesh Chandra (Poonia) < notifications@github.com> wrote:
Hi, Which simulator I can use for Autonomous Surface Vessels. Can you suggest me better simulator for path planning and collision avoidance?
— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/uuvsimulator/uuv_simulator/issues/174?email_source=notifications&email_token=AB77UJMZDKLDTPGUNZYZCWDP5NKIRA5CNFSM4EJFYKB2YY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGODZBI7CA#issuecomment-507678600, or mute the thread https://github.com/notifications/unsubscribe-auth/AB77UJNDFHOEHBKIBM3HGS3P5NKIRANCNFSM4EJFYKBQ .
Unfortunately, usv_sim_lsa is only for surface vehicles. I need to use the uuv_simulator package because I also need to simulate uuv's.
Hi @eriman1 are the URDF models still helpful for you ?
Hi, I am trying to build a simulator for WAM-V using this package. Since WAM-V is a surface vessel, I tried to adjust the parameters for mass, volumn, fluid density in the underwater_object_ros_plugin, so that the model can float on the surface of the water. This is the part I changed.
However, no matter how I adjust the parameters, the WAM-V model is always partially submerged.
Is there any way to make this plugin work for WAM-V? Thanks