Skip to content

markusbuchholz/gazebosim_bluerov2_ardupilot_sitl

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

3 Commits
 
 
 
 
 
 
 
 
 
 

Repository files navigation

BlueROV2 simulation SITL in Gazebo

The following repository offers the BlueROV2 simulation SITL with GazeboSim. Users can plan complex missions using ROS 2, ArduPilot or QGroundControl by defining waypoints and survey grids.

SITL allows you to simulate the vehicle hardware and firmware (ArduSub ) on your host directly.

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_bluerov2_ardupilot_sitl.git

cd gazebosim_bluerov2_ardupilot_sitl/bluerov2_ardupilot_SITL/docker

sudo ./build.sh

Build in Docker

Adjust in run.sh.

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

Run Gazebo BlueRov2 simulator

Note:

  • IMPORTANT: Run Gazebo first as it contains the ArduPilot plugin. Later, start the ArduPilot SITL (Rover) simulator. Lastly, you can run QGroundControl.
sudo docker exec -it bluerov2_sitl /bin/bash

ros2 launch move_blueboat launch_robot_simulation.launch.py

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 bluerov2_sitl /bin/bash

cd ../ardupilot

sim_vehicle.py -v ArduSub -f vectored_6dof --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

Start QGC (outside Docker)

./QGroundControl.AppImage

Move BlueRov2

Move the vehicle using Ardusub to navigate the designated waypoints, utilizing either ROS 2 or ArduPilot.

# It is recommended to Arm the vehicle first

arm throttle
ros2 launch move_blueboat wp_rov
cd  /gz_ws/src/extras_rov

python3 wp_pos_req.py

Change the Motion Velocity

The following program, before motion, changes the ArduSub parameters influencing the global velocity motion for the vehicle.

  • WPNAV_SPEED - for horizontal speed
  • WPNAV_SPEED_DN - for descent speed
  • WPNAV_SPEED_UP - for climb speed
ros2 launch move_blueboat wp_velo_rov

PlotJuggler

ros2 run plotjuggler plotjuggler

Run Motor Test (PWM control)

Setting the ArduSub RCPassThru parameter allows setting PWM directly for individual motors with values ranging from 1100 to 1900.

ros2 run plotjuggler plotjuggler

cd extras

python3 test_motor_thrust.py

image

Performance Charts

Details

image

Acknowledgement

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published