Skip to content

Latest commit

 

History

History
275 lines (176 loc) · 8.81 KB

File metadata and controls

275 lines (176 loc) · 8.81 KB

BlueBoat simulation SITL with GazeboSim and QGC

The following repository offers the BlueBoat simulation SITL with GazeboSim. Users can plan complex missions using QGroundControl by defining waypoints and survey grids.

BlueBoat follows waypoints

image

BlueBoat performs a survey

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

git clone https://github.com/markusbuchholz/gazebosim_blueboat_ardupilot_sitl.git

cd /gazebosim_blueboat_ardupilot_sitl/blueboat_sitl/docker

sudo ./build.sh

Run

Note:

Adjust these lines in run.sh

local_gz_ws="/home/markus/blueboat_ardupilot_SITL/gz_ws"
local_SITL_Models="/home/markus/blueboat_ardupilot_SITL/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
 

Start QGC (outside Docker)

./QGroundControl.AppImage

Run GazeboSim inside Docker

sudo docker exec -it blueboat_sitl /bin/bash

ros2 launch move_blueboat launch_robot_simulation.launch.py

Run SITL

Notes:

  • IMPORTANT: Run GazbenSim first as it holds the ArduPilot plugin, which you can connect with the ArduPilot SITL (Rover) simulator!

  • 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:

local_gz_ws="/home/markus/blueboat_ardupilot_SITL/gz_ws"
local_SITL_Models="/home/markus/blueboat_ardupilot_SITL/SITL_Models"
sudo docker exec -it blueboat_sitl /bin/bash

cd ../ardupilot

sim_vehicle.py -v Rover -f gazebo-rover --model JSON --map --console -l 55.99541530863445,-3.3010225004910683,0,0

# if you need to recompile 
Tools/environment_install/install-prereqs-ubuntu.sh -y

# after recompiling 
. ~/.profile

Path Planner Interface

The Mavlink protocol offers simple commands to the vehicle to navigate to waypoints so that the vehicle can perform its mission. The following can be considered an interface to the vehicle (simulator). It accepts waypoints from the path planner as arguments from the terminal and sends them to ArduRover for execution.

# Launch Gazebo and ArduRover before executing the mission.

cd extras_boat
python3 args_mission_planner_gps.py --positions "0,0;5,5;0,0;10,-10;-5,5;0,0;30,30;0,0"

You can launch the program with "hard-coded" waypoints.

cd extras_boat
python3 mission_planner_gps.py

Run the following program to feed ArduRover with waypoints one by one. Once the program activates, it will execute a constant flow of waypoints from the terminal.

cd extras_boat
python3 loop_mission_planner_gps.py

Guided mode with Dynamic Position

Following the program accepts the X and Y coordinates of the desired waypoint through terminal input. The vehicle navigates to position and maintains its dynamic position, ensuring stability between waypoints despite external disturbances.

cd extras_boat
python3 loop_mission_planner_gps_dynamic_position.py

The following program accepts the constant flow of waypoints from the terminal and performs the dynamic position in the last.

cd extras_boat
python3 mission_planner_gps_dynamic_position.py

ROS 2 mission controller with Dynamic Position

The path planner can execute the mission by feeding the mission controller with waypoints. Each waypoint will be executed, and the boat will stay at the last waypoint in a dynamic position, waiting for the next command from the controller.

# Start Gazebo
ros2 launch move_blueboat launch_robot_simulation.launch.py

# Start Controller
ros2 run move_blueboat dp_beacon_dvl_run_boat_waypoint

# Publish waypoints
ros2 topic pub -1 /waypoints std_msgs/Float64MultiArray "{data: [5.0, 5.0]}" -1

Control BlueBoat using joystick

  • Joystick handler left: left/right
  • Joystick handler right: forward/backward
ros2 launch move_blueboat manual_control_boat_sim.launch.py

ROS 2 topics

# BlueBoat
/model/blueboat/joint/motor_port_joint/cmd_thrust
/model/blueboat/joint/motor_stbd_joint/cmd_thrust
/model/blueboat/navsat
/model/blueboat/odometry

Control BlueBoat directly using pymavlink

Note:

  • Find useful examples in folder èxtras_boat.
sudo pip3 install pymavlink

Run scripts

cd extras_boat

python3 run_boat.py

PlotJuggler

ros2 run plotjuggler plotjuggler

image

Waves Control

Type Waves Controlin the GazeboSim menu (3 dots) to access the control panel of ocean disturbances.

image

ASV Mission Planner

The mission planner provides the opportunity to define the start, goal, obstacles, and waypoints for the ASV to follow. Users can plan missions using the RRT* or A* algorithm. The Simple Path constructs the path based on the start, goal, and waypoints. After the path planner finds the path, the user can send the path to run ROS 2 program, which reads the path and moves the vehicle (default in Gazebo).

#run Gazebo

ros2 launch move_blueboat launch_robot_simulation.launch.py

#start path planner GUI

cd gz_ws/src/move_blueboat/move_blueboat

python3 coralguide_asv_mission_planner.py

image

MAVProxy Cheatsheet

For example:

arm throttle
mode
mode GUIDED
disarm

References