srmainwaring / asv_wave_sim

This package contains plugins that support the simulation of waves and surface vessels in Gazebo.
GNU General Public License v3.0
117 stars 32 forks source link

Include HydrodynamicsPlugin in URDF file #11

Closed vinz-uts closed 3 years ago

vinz-uts commented 3 years ago

Hi, I'm trying to use the asv_wave_sim package to simulate an autonomous buoy in gazebo. I've a .urdf file that describes the buoy and the motors with some plugin for simulate imu, thrusters, etc in ROS. I'm trying to include the libHydrodynamicsPlugin.so to perform the buoyancy of the main <link> of the buoy, but without success. I'm reading the documentation and the examples in the wiki but i see only the tag for the .sdf file. I've tried to include the same tag in the <gazebo> tag of the .urdf but not works: the buoy go down. Can any help me to understand how can include the HydrodynamicsPlugin in a .urdf file? Thanks for your attention.

srmainwaring commented 3 years ago

@vinz-uts to include the plugin in a URDF file you need to surround the <plugin> element in a <gazebo> element. This is an extract from the URDF for a sailing boat:

https://github.com/srmainwaring/rs750/blob/master/rs750_description/urdf/rs750.gazebo

<?xml version="1.0" ?>
<robot name="rs750">
  <gazebo>
    <!-- Hydrodynamics plugin -->
    <plugin filename="libHydrodynamicsPlugin.so" name="hydrodynamics">
      <!-- Wave Model -->
      <wave_model>ocean</wave_model>
      <!-- Hydrodynamics -->
      <damping_on>true</damping_on>
      <viscous_drag_on>true</viscous_drag_on>
      <pressure_drag_on>true</pressure_drag_on>
      <!-- Markers -->
      <markers>
        <update_rate>30</update_rate>
        <water_patch>false</water_patch>
        <waterline>false</waterline>
        <underwater_surface>false</underwater_surface>
      </markers>
    </plugin>
  <gazebo>
</robot>

If you are doing this, but still see the buoy sinking, then it may be that the plugin is not loading correctly. In which case you need to ensure the Gazebo resource paths are set correctly:

GAZEBO_RESOURCE_PATH=/path/to/media/and/materials/etc
GAZEBO_PLUGIN_PATH=/path/to/asv_wave/plugins
GAZEBO_MODEL_PATH=/path/to/your/models

If you still don't have any luck, can you run Gazebo with the --verbose flag and post the log. If Gazebo attempts to load the plugin and doesn't find it there will be a message.

vinz-uts commented 3 years ago

Thanks for your fast replay, I've done some test: in the last week I added to my code the same lines that you have posted. This is my .urdf file:

<?xml version="1.0"?>
<robot name="asv">

  <link name="body_frame">
    <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
         <box size="10 4 2"/>
        </geometry>
        <material name="white_rviz">
         <color rgba="1 0 0 1"/>
       </material>
    </visual>
    <collision>
      <geometry>
        <box size="10 4 2"/>
      </geometry>
    </collision>
    <inertial>
      <origin xyz="0.0036 0.004 0.05"/>
      <mass value="20.9057"/>
      <inertia ixx="0.7732" ixy="0.0096" ixz="2.9732e-04"
               iyy="0.773" iyz="-0.0085"
               izz="1.2544"/>
    </inertial>
  </link>

  <gazebo reference="body_frame">
    <material>Gazebo/Residential</material>
  </gazebo>

  <gazebo>
    <!-- Hydrodynamics plugin -->
    <plugin filename="libHydrodynamicsPlugin.so" name="hydrodynamics">
      <!-- Wave Model -->
      <wave_model>ocean_waves</wave_model>
      <!-- Hydrodynamics -->
      <damping_on>true</damping_on>
      <viscous_drag_on>true</viscous_drag_on>
      <pressure_drag_on>true</pressure_drag_on>
      <!-- Markers -->
      <markers>
        <update_rate>30</update_rate>
        <water_patch>false</water_patch>
        <waterline>false</waterline>
        <underwater_surface>false</underwater_surface>
      </markers>
    </plugin>
  </gazebo>

</robot>

This file is in a package in my ros workspace, and, in the same workspace, there are also the asv_wave_sim package. Maybe, as you tell me, the problem can be found in the gazebo environmental variables that, in my case, was empty. I've try to add in my .bashrc file the line source /usr/share/gazebo-9/setup.sh and now I think that I've to add the path to the asv_wave_sim plugins. I don't understand what path I've to add to the variables: is ros_ws/src/asv_wave_sim/asv_wave_sim_gazebo_plugins/src the folder of the asv_wave_sim plugins or ros_ws/devel/lib? If I run Gazebo with the --verbose flag, I don't see any issue, but when I push the play button on Gazebo, the "buoy" sinking and a lot of [Err] [Wavefield.cc:854] Wavefield is too small are throwed.

Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://applicon:38843/

SUMMARY
========

PARAMETERS
 * /gazebo/enable_ros_network: True
 * /robot_description: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.10
 * /use_sim_time: True

NODES
  /
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    spawn_urdf (gazebo_ros/spawn_model)

auto-starting new master
process[master]: started with pid [19187]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 07d44564-9d45-11eb-a20f-0092c9083f48
process[rosout-1]: started with pid [19198]
started core service [/rosout]
process[gazebo-2]: started with pid [19205]
process[gazebo_gui-3]: started with pid [19210]
process[spawn_urdf-4]: started with pid [19215]
Gazebo multi-robot simulator, version 9.16.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Wrn] [GuiIface.cc:200] g/gui-plugin is really loading a SystemPlugin. To load a GUI plugin please use --gui-client-plugin 
Gazebo multi-robot simulator, version 9.16.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1618420542.566465747]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1618420542.573089281]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.43.47
[ INFO] [1618420542.733561936]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1618420542.739210920]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.43.47
[Msg] Loading world file [/home/udoo/ares_ros_ws/src/asv_wave_sim/asv_wave_sim_gazebo/worlds/ocean.world]
[ INFO] [1618420543.866458971]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[Msg] Parameter found - setting <static> to <0>.
[Msg] Parameter found - setting <update_rate> to <30>.
[Msg] Parameter found - setting <wave_patch> to <0>.
[Msg] Parameter found - setting <wave_patch_size> to <4 4>.
[Msg] Parameter found - setting <size> to <1000 1000>.
[Msg] Parameter found - setting <cell_count> to <50 50>.
[Msg] Parameter found - setting <number> to <3>.
[Msg] Parameter found - setting <amplitude> to <0.1>.
[Msg] Parameter found - setting <period> to <7>.
[Msg] Parameter <phase> not found: Using default value of <0>.
[Msg] Parameter found - setting <direction> to <1 1>.
[Msg] Parameter found - setting <scale> to <1.5>.
[Msg] Parameter found - setting <angle> to <0.4>.
[Msg] Parameter found - setting <steepness> to <1>.
[ INFO] [1618420544.019068366]: Physics dynamic reconfigure ready.
[Msg] Parameter found - setting <wave_model> to <ocean_waves>.
[Msg] Parameter found - setting <damping_on> to <1>.
[Msg] Parameter found - setting <viscous_drag_on> to <1>.
[Msg] Parameter found - setting <pressure_drag_on> to <1>.
[Msg] Parameter found - setting <cDampL1> to <1e-06>.
[Msg] Parameter found - setting <cDampL2> to <1e-06>.
[Msg] Parameter found - setting <cDampR1> to <1e-06>.
[Msg] Parameter found - setting <cDampR2> to <1e-06>.
[Msg] Parameter found - setting <cPDrag1> to <100>.
[Msg] Parameter found - setting <cPDrag2> to <100>.
[Msg] Parameter found - setting <fPDrag> to <0.4>.
[Msg] Parameter found - setting <cSDrag1> to <100>.
[Msg] Parameter found - setting <cSDrag2> to <100>.
[Msg] Parameter found - setting <fSDrag> to <0.4>.
[Msg] Parameter found - setting <vRDrag> to <1>.
[Msg] Parameter found - setting <update_rate> to <30>.
[Msg] Parameter found - setting <water_patch> to <0>.
[Msg] Parameter found - setting <waterline> to <0>.
[Msg] Parameter found - setting <underwater_surface> to <0>.
[Msg] links:  1
[Msg] meshes: 1
[Msg] Water patch size: 0
[Msg] Parameter found - setting <wave_model> to <ocean_waves>.
[Msg] Parameter found - setting <damping_on> to <1>.
[Msg] Parameter found - setting <viscous_drag_on> to <1>.
[Msg] Parameter found - setting <pressure_drag_on> to <1>.
[Msg] Parameter <cDampL1> not found: Using default value of <1e-06>.
[Msg] Parameter <cDampL2> not found: Using default value of <1e-06>.
[Msg] Parameter <cDampR1> not found: Using default value of <1e-06>.
[Msg] Parameter <cDampR2> not found: Using default value of <1e-06>.
[Msg] Parameter <cPDrag1> not found: Using default value of <100>.
[Msg] Parameter <cPDrag2> not found: Using default value of <100>.
[Msg] Parameter <fPDrag> not found: Using default value of <0.4>.
[Msg] Parameter <cSDrag1> not found: Using default value of <100>.
[Msg] Parameter <cSDrag2> not found: Using default value of <100>.
[Msg] Parameter <fSDrag> not found: Using default value of <0.4>.
[Msg] Parameter <vRDrag> not found: Using default value of <1>.
[Msg] Parameter found - setting <update_rate> to <30>.
[Msg] Parameter found - setting <water_patch> to <0>.
[Msg] Parameter found - setting <waterline> to <0>.
[Msg] Parameter found - setting <underwater_surface> to <0>.
[Msg] Shape:      shape
[Msg] Scale:      1 1 1
[Msg] Type:       30000
[Msg] Type:       BOX_SHAPE
[Msg] Size:       10 4 2
[Msg] Vertex:     24
[Msg] links:  1
[Msg] meshes: 1
[Msg] Water patch size: 16.4317
[spawn_urdf-4] process has finished cleanly
log file: /home/udoo/.ros/log/07d44564-9d45-11eb-a20f-0092c9083f48/spawn_urdf-4*.log
[Msg] Parameter <static> not found: Using default value of <0>.
[Msg] Wavefield Visual received message on topic [/gazebo/ocean_world/response]
[Msg] number:     3
[Msg] scale:      1.5
[Msg] angle:      0.4
[Msg] period:     7
[Msg] amplitude:  0.0666667, 0.1, 0.15, 
[Msg] wavenumber: 0.123319, 0.0822124, 0.0548083, 
[Msg] omega:      1.09933, 0.897598, 0.732886, 
[Msg] phase:      0, 0, 0, 
[Msg] steepness:  1, 1, 1, 
[Msg] direction:  0.926649 0.375928
[Msg] direction:  0.707107 0.707107
[Msg] direction:  0.375928 0.926649
[Msg] Parameter <static> not found: Using default value of <0>.
[Msg] Wavefield Visual received message on topic [/gazebo/ocean_world/response]
[Msg] number:     3
[Msg] scale:      1.5
[Msg] angle:      0.4
[Msg] period:     7
[Msg] amplitude:  0.0666667, 0.1, 0.15, 
[Msg] wavenumber: 0.123319, 0.0822124, 0.0548083, 
[Msg] omega:      1.09933, 0.897598, 0.732886, 
[Msg] phase:      0, 0, 0, 
[Msg] steepness:  1, 1, 1, 
[Msg] direction:  0.926649 0.375928
[Msg] direction:  0.707107 0.707107
[Msg] direction:  0.375928 0.926649
[Msg] Wavefield Visual received message on topic [/gazebo/ocean_world/response]
[Msg] number:     3
[Msg] scale:      1.5
[Msg] angle:      0.4
[Msg] period:     7
[Msg] amplitude:  0.0666667, 0.1, 0.15, 
[Msg] wavenumber: 0.123319, 0.0822124, 0.0548083, 
[Msg] omega:      1.09933, 0.897598, 0.732886, 
[Msg] phase:      0, 0, 0, 
[Msg] steepness:  1, 1, 1, 
[Msg] direction:  0.926649 0.375928
[Msg] direction:  0.707107 0.707107
[Msg] direction:  0.375928 0.926649
[Msg] origin:   -2825.12 14.3836 0
[Err] [Wavefield.cc:854] Wavefield is too small
[Msg] origin:   -5641.91 36.9918 0
[Err] [Wavefield.cc:854] Wavefield is too small

Thanks for your help!

vinz-uts commented 3 years ago

@srmainwaring thanks for yours advices. I've solved the problem, it was the value of Gazebo paths. I have added the ros_ws/devel/lib to the GAZEBO_PLUGIN_PATH variable and fixed a few of other problem. But I don't understand why before the models of the box, the duck, etc founded in asv_wave_sim_gazebo/models was working fine and the buoy was not working. Do not this models load also the same plugin? Thanks again.

srmainwaring commented 3 years ago

@vinz-uts great! I'm glad you managed to resolve the problem.

It might be that you didn't configure the additional exports in the package.xml file in the package defining your model? You can use the package.xml in asv_wave_sim_gazebo where the example models are defined as a template:

https://github.com/srmainwaring/asv_wave_sim/blob/524a6bdab819ed422c85d19ccff0ceef2fddcdf5/asv_wave_sim_gazebo/package.xml#L21-L25

These lines ensure the Gazebo environment variables are updated when you run

source ~/ros_ws/devel/setup.bash