Skip to content

Commit

Permalink
Gazebo: support Gazebo Harmonic and Garden
Browse files Browse the repository at this point in the history
- Update package.xml and cmake to handle both versions.
- Add gz msg include dependencies.
- Update README.
- Fix CI.

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Dec 16, 2023
1 parent 0316763 commit e5a5a9f
Show file tree
Hide file tree
Showing 5 changed files with 63 additions and 16 deletions.
32 changes: 28 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
32 changes: 22 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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:

Expand All @@ -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).
Expand All @@ -43,18 +43,30 @@ 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
brew update
brew install rapidjson
```

Ensure the `GZ_VERSION` environment variable is set to either
`garden` or `harmonic`.

Clone the repo and build:

```bash
Expand Down Expand Up @@ -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).
11 changes: 9 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,15 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rapidjson-dev</build_depend>
<build_depend>libgz-cmake3-dev</build_depend>
<build_depend>libgz-sim7-dev</build_depend>

<!-- Harmonic -->
<depend condition="$GZ_VERSION == harmonic">gz-cmake3</depend>
<depend condition="$GZ_VERSION == harmonic">gz-sim8</depend>
<!-- Garden (default) -->
<depend condition="$GZ_VERSION == garden">gz-cmake3</depend>
<depend condition="$GZ_VERSION == garden">gz-sim7</depend>
<depend condition="$GZ_VERSION == ''">gz-cmake3</depend>
<depend condition="$GZ_VERSION == ''">gz-sim7</depend>

<test_depend>ament_lint_auto</test_depend>

Expand Down
2 changes: 2 additions & 0 deletions src/ArduPilotPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
#include <sstream>
#include <vector>

#include <gz/msgs/imu.pb.h>
#include <gz/msgs/laserscan.pb.h>

#include <gz/common/SignalHandler.hh>
#include <gz/msgs/Utility.hh>
Expand Down
2 changes: 2 additions & 0 deletions src/ParachutePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include <string>

#include <gz/msgs/entity_factory.pb.h>

#include <gz/plugin/Register.hh>
#include <gz/common/Profiler.hh>
#include <gz/math/Pose3.hh>
Expand Down

0 comments on commit e5a5a9f

Please sign in to comment.