From 060de680d5d055f0a440f659b67d91da46f4761c Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Sat, 16 Dec 2023 13:42:25 +0000 Subject: [PATCH] Gazebo: support Gazebo Harmonic and Garden - Update package.xml and cmake to handle both versions. - Add gz msg include dependencies. - Update README. - Fix CI - switch include order. Signed-off-by: Rhys Mainwaring --- CMakeLists.txt | 32 ++++++++++++++++++++++++++++---- README.md | 32 ++++++++++++++++++++++---------- package.xml | 11 +++++++++-- src/ArduPilotPlugin.cc | 4 +++- src/ParachutePlugin.cc | 2 ++ 5 files changed, 64 insertions(+), 17 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4874a7dc..d8ff8dde 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,11 +16,35 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON) # --------------------------------------------------------------------------- # # Find gz-sim and dependencies. -find_package(gz-cmake3 REQUIRED) -set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) -gz_find_package(gz-sim7 REQUIRED) -set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) +# Harmonic +if("$ENV{GZ_VERSION}" STREQUAL "harmonic") + find_package(gz-cmake3 REQUIRED) + set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) + + gz_find_package(gz-sim8 REQUIRED) + set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR}) + + message(STATUS "Compiling against Gazebo Harmonic") +# Garden +elseif("$ENV{GZ_VERSION}" STREQUAL "garden") + find_package(gz-cmake3 REQUIRED) + set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) + + gz_find_package(gz-sim7 REQUIRED) + set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) + + message(STATUS "Compiling against Gazebo Garden") +# Default to Garden +else() + find_package(gz-cmake3 REQUIRED) + set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) + + gz_find_package(gz-sim7 REQUIRED) + set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) + + message(STATUS "Compiling against Gazebo Garden") +endif() # --------------------------------------------------------------------------- # # Find RapidJSON. diff --git a/README.md b/README.md index df5aec92..4ab25bd5 100644 --- a/README.md +++ b/README.md @@ -4,11 +4,11 @@ [![ccplint](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccplint.yml/badge.svg)](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccplint.yml) [![cppcheck](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccpcheck.yml/badge.svg)](https://github.com/ArduPilot/ardupilot_gazebo/actions/workflows/ccpcheck.yml) -This is the official ArduPilot plugin for [Gazebo Sim](https://gazebosim.org/home). +This is the official ArduPilot plugin for [Gazebo](https://gazebosim.org/home). It replaces the previous [`ardupilot_gazebo`](https://github.com/khancyr/ardupilot_gazebo) -plugin and provides support for the latest release of the Gazebo simulator -[(Gazebo Garden)](https://gazebosim.org/docs/garden/install). +plugin and provides support for the recent releases of the Gazebo simulator +[(Gazebo Garden)](https://gazebosim.org/docs/garden/install) and [(Gazebo Harmonic)](https://gazebosim.org/docs/harmonic/install). It also adds the following features: @@ -18,19 +18,19 @@ It also adds the following features: the Gazebo time for debugging. - Improved 3D rendering using the `ogre2` rendering engine. -The project comprises a Gazebo Sim plugin to connect to ArduPilot SITL +The project comprises a Gazebo plugin to connect to ArduPilot SITL (Software In The Loop) and some example models and worlds. ## Prerequisites -Gazebo Sim Garden is supported on Ubuntu 20.04 (Focal) and 22.04 (Jammy). +Gazebo Garden or Harmonic is supported on Ubuntu 22.04 (Jammy). If you are running Ubuntu as a virtual machine you will need at least Ubuntu 20.04 in order to have the OpenGL support required for the -`ogre2` render engine. Gazebo Sim and ArduPilot SITL will also run on macOS -(Big Sur and Monterey; Intel and M1 devices). +`ogre2` render engine. Gazebo and ArduPilot SITL will also run on macOS +(Big Sur, Monterey and Venturua; Intel and M1 devices). -Follow the instructions for a -[binary install of Gazebo Garden](https://gazebosim.org/docs/garden/install) +Follow the instructions for a binary install of +[Gazebo Garden](https://gazebosim.org/docs/garden/install) or [Gazebo Harmonic](https://gazebosim.org/docs/harmonic/install) and verify that Gazebo is running correctly. Set up an [ArduPilot development environment](https://ardupilot.org/dev/index.html). @@ -43,11 +43,20 @@ Install additional dependencies: ### Ubuntu +Gazebo Garden: + ```bash sudo apt update sudo apt install libgz-sim7-dev rapidjson-dev ``` +Or Gazebo Harmonic: + +```bash +sudo apt update +sudo apt install libgz-sim8-dev rapidjson-dev +``` + ### macOS ```bash @@ -55,6 +64,9 @@ brew update brew install rapidjson ``` +Ensure the `GZ_VERSION` environment variable is set to either +`garden` or `harmonic`. + Clone the repo and build: ```bash @@ -233,4 +245,4 @@ Click on the images to see further details. ## Troubleshooting For issues concerning installing and running Gazebo on your platform please -consult the Gazebo Sim documentation for [troubleshooting frequent issues](https://gazebosim.org/docs/garden/troubleshooting#ubuntu). +consult the Gazebo documentation for [troubleshooting frequent issues](https://gazebosim.org/docs/harmonic/troubleshooting#ubuntu). diff --git a/package.xml b/package.xml index d1f7de5e..c6a1b698 100644 --- a/package.xml +++ b/package.xml @@ -11,8 +11,15 @@ ament_cmake rapidjson-dev - libgz-cmake3-dev - libgz-sim7-dev + + + gz-cmake3 + gz-sim8 + + gz-cmake3 + gz-sim7 + gz-cmake3 + gz-sim7 ament_lint_auto diff --git a/src/ArduPilotPlugin.cc b/src/ArduPilotPlugin.cc index cad587f0..b2a3a25b 100755 --- a/src/ArduPilotPlugin.cc +++ b/src/ArduPilotPlugin.cc @@ -19,6 +19,9 @@ #include #include +#include +#include + #include #include #include @@ -26,7 +29,6 @@ #include #include - #include #include #include diff --git a/src/ParachutePlugin.cc b/src/ParachutePlugin.cc index 6074d1c1..5b283661 100644 --- a/src/ParachutePlugin.cc +++ b/src/ParachutePlugin.cc @@ -17,6 +17,8 @@ #include "ParachutePlugin.hh" +#include + #include #include