Skip to content

markusbuchholz/marine-robotics-sim-framework

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

36 Commits
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Marine Robotics Simulation Framework

This repository offers a simulation framework designed to evaluate motion control algorithms in tethered multi-robot systems operating within dynamic marine environments. Specifically, it focuses on the coordinated operation of an Autonomous Underwater Vehicle (AUV) and an Autonomous Surface Vehicle (ASV) constrained by tether. The framework utilizes GazeboSim, enhanced with realistic marine environment plugins and ArduPilot's Software-in-the-Loop (SITL) mode.

gazebo

dancing_tetheronline

System Architecture

image

Prerequisites

  • Download and Install QGroundControl (optional).
  • Install NVIDIA Container Toolkit to support Docker to access GPU (required).
  • Repository has been tested on: Ubuntu 22.04, Ubuntu 24.04, ArchLinux (Kernel 6.8).

Build Docker

git clone https://github.com/markusbuchholz/marine-robotics-sim-framework/git

cd marine-robotics-sim-framework//bluerov2_ardupilot_SITL/docker

sudo ./build.sh

Run Docker

Adjust in run.sh.

local_gz_ws="/home/markus/underwater/marine-robotics-sim-framework/gz_ws"
local_SITL_Models="/home/markus/underwater/marine-robotics-sim-framework/SITL_Models"
sudo ./run.sh

colcon build

source install/setup.bash

cd ../gz_ws

colcon build --symlink-install --merge-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DBUILD_TESTING=ON -DCMAKE_CXX_STANDARD=17

source install/setup.bash

source gazebo_exports.sh
 

Run simulator

Note:

  • IMPORTANT: Run GazeboSim first as it contains the ArduPilot plugin. Later, start the ArduPilot SITL (ArduSub, Rover). Lastly, you can run QGroundControl.
ros2 launch move_blueboat multirobot_mission_simulation.launch.py

You can always connect to running Docker containers from other terminals,

sudo docker exec -it marine_robotics_sitl /bin/bash

Run SITL

Notes:

  • The flag -l is the localization (lat,lon,alt,heading). Check your favorite location with Google Maps.
  • sim_vehicle.py --help -prints all available commands and flags.
  • in run.sh adjust these two lines for your host specific:
sudo docker exec -it marine_robotics_sitl /bin/bash

cd ../ardupilot

# ArduSub (BlueROV2)
sim_vehicle.py -v ArduSub -f vectored_6dof --model JSON --map --console -l 55.99541530863445,-3.3010225004910683,0,0 -I0

# ArduRover (BlueBoat)
sim_vehicle.py -v Rover -f gazebo-rover --model JSON --map --console -l 55.99541530863445,-3.3010225004910683,0,0 -I1

ROS 2 Interfaces

There are simple ROS 2 interfaces to wrap mavlink.

gz_ws/extras_interface

python3 ros2_bluerov2_interface.py

For the BlueRov2, you can start with a simple ROS 2 interface and command motion,

gz_ws/extras_interface

python3 ros2_wp_rov_pusher.py

Use the following topics to move the vehicle,

ros2 topic pub --once /bluerov2/waypoint std_msgs/msg/Float32MultiArray "{data: [0.0, 0.0, -2.0]}"

or

ros2 topic pub --once /bluerov2/waypoint std_msgs/msg/Float32MultiArray "{data: [1.0, 0.0, -2.0, 2.0, 2.0, -2.0, 3.0, -2.0, -4.0]}"

ROS 2 BlueBoat

gz_ws/extras_interface

python3 ros2_blueboat_interface.py

Tether modeling

We consider a tether which is composed of N spheres, each of mass m and radius r. The spheres are connected sequentially, with each pair of adjacent spheres connected by a ball-type joint. The joint allows the spheres to rotate relative to each other in two perpendicular directions, simulating the flexibility of an actual underwater tether. We consider the tether to hold the catenary shape.

The length of the tether can be adjusted using multirobot_mission_simulation.launch file.
The physical parameters of the tether behavior can be modified using model.sdf in the corresponding tether_part.

<?xml version="1.0" ?>
<sdf version="1.6">
  <model name="tether_part">        
    <plugin
        filename="gz-waves1-hydrodynamics-system"
        name="gz::sim::systems::Hydrodynamics">
        <!-- Adjust buoyancy settings for near-neutral buoyancy -->
        <buoyancy>
          <volume>0.000025</volume>
          <center_of_buoyancy>0 0 0</center_of_buoyancy>
          <mass_density>1000</mass_density> 
        </buoyancy>
    </plugin>
    <link name="base_link">
      <visual name="visual">
        <geometry>
          <sphere>
            <radius>0.025</radius> <!-- Size of the buoy -->
          </sphere>
        </geometry>
        <material>
          <ambient>1.0 0.0 0.0 1.0</ambient>  <!-- Bright red -->
          <diffuse>1.0 0.0 0.0 1.0</diffuse>  <!-- Bright red -->
          <specular>0.8 0.8 0.8 1.0</specular> <!-- Slightly reflective -->
        </material>
      </visual>
      
      <collision name="collision">
        <geometry>
          <sphere>
            <radius>0.01</radius> <!-- Smaller collision radius -->
          </sphere>
        </geometry>
      </collision>
      
      <inertial>
        <mass>0.00429</mass> <!-- Mass adjusted for neutral buoyancy -->
        <inertia>
          <!-- Recalculated based on the solid sphere inertia formula -->
          <ixx>0.00000006</ixx> <!-- 2/5 * mass * radius^2 -->
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>0.00000006</iyy>
          <iyz>0.0</iyz>
          <izz>0.00000006</izz>
        </inertia>
      </inertial>
    </link>
  </model>
</sdf>

Simulate the position of the tether

Run,

cd extras_tether

python3 dynamic_update_cabel_pos.py

image


Start QGC (outside Docker)

./QGroundControl.AppImage

PlotJuggler

ros2 run plotjuggler plotjuggler

Poster

Poster during workshop

Acknowledgement

References

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published