diff --git a/CMakeLists.txt b/CMakeLists.txt index 6dd9a22..b9744ab 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,7 +18,7 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON) # Find gz-sim and dependencies. # Harmonic -if("$ENV{GZ_VERSION}" STREQUAL "harmonic") +if("$ENV{GZ_VERSION}" STREQUAL "harmonic" OR NOT DEFINED "ENV{GZ_VERSION}") find_package(gz-cmake3 REQUIRED) set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) @@ -33,7 +33,7 @@ if("$ENV{GZ_VERSION}" STREQUAL "harmonic") message(STATUS "Compiling against Gazebo Harmonic") # Garden (default) -elseif("$ENV{GZ_VERSION}" STREQUAL "garden" OR NOT DEFINED "ENV{GZ_VERSION}") +elseif("$ENV{GZ_VERSION}" STREQUAL "garden") find_package(gz-cmake3 REQUIRED) set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR}) diff --git a/README.md b/README.md index 4ab25bd..ca92be3 100644 --- a/README.md +++ b/README.md @@ -24,6 +24,7 @@ The project comprises a Gazebo plugin to connect to ArduPilot SITL ## Prerequisites Gazebo Garden or Harmonic is supported on Ubuntu 22.04 (Jammy). +Harmonic is recommended. 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 and ArduPilot SITL will also run on macOS @@ -43,14 +44,27 @@ Install additional dependencies: ### Ubuntu -Gazebo Garden: +Recommended - Use rosdep with +[osrf's rosdep rules](https://github.com/osrf/osrf-rosdep?tab=readme-ov-file#1-use-rosdep-to-resolve-gazebo-libraries) +to manage all dependencies. This is driven off of the environment variable `GZ_VERSION`. + +```bash +export GZ_VERSION=harmonic # or garden +sudo bash -c 'wget https://raw.githubusercontent.com/osrf/osrf-rosdep/master/gz/00-gazebo.list -O /etc/ros/rosdep/sources.list.d/00-gazebo.list' +rosdep update +rosdep resolve gz-harmonic +# Navigate to your ROS workspace before the next command. +rosdep install --from-paths src --ignore-src -y +``` + +Manual - Gazebo Garden Dependencies: ```bash sudo apt update sudo apt install libgz-sim7-dev rapidjson-dev ``` -Or Gazebo Harmonic: +Manual - Gazebo Harmonic Dependencies: ```bash sudo apt update diff --git a/package.xml b/package.xml index c6a1b69..1e67aee 100644 --- a/package.xml +++ b/package.xml @@ -12,14 +12,14 @@ rapidjson-dev - + gz-cmake3 gz-sim8 - + gz-cmake3 + gz-sim8 + gz-cmake3 gz-sim7 - gz-cmake3 - gz-sim7 ament_lint_auto