Skip to content

Commit

Permalink
ROS: build as ament package if ROS available (#53)
Browse files Browse the repository at this point in the history
- Add ROS ament package configuration.
- Build as ament package if possible, otherwise revert to standard cmake.
- Use QUIET in find_package for ament_cmake.
- Add build dependencies on rapidjson-dev, libgz-cmake3-dev, libgz-sim7-dev.

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
  • Loading branch information
srmainwaring committed Apr 17, 2023
1 parent 0753b06 commit a739479
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 30 deletions.
92 changes: 62 additions & 30 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,61 +1,93 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
project(ardupilot_gazebo)

#============================================================================
# Initialize the project
#============================================================================
project(ardupilot_sitl_gazebo)

#------------------------------------------------------------------------
# Compile as C++14
# --------------------------------------------------------------------------- #
# If ament_cmake is found build as an ament package, otherwise ignore.
# This is so the system may be built for Gazebo only, if ROS is not available.
find_package(ament_cmake QUIET)
if(${ament_cmake_FOUND})
message("Building ${PROJECT_NAME} as an `ament_cmake` project.")
endif()

# --------------------------------------------------------------------------- #
# Compile as C++14.
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

#============================================================================
# Find gz-cmake
#============================================================================
find_package(gz-cmake3 3.0.0 REQUIRED)
# --------------------------------------------------------------------------- #
# Find gz-sim and dependencies.
find_package(gz-cmake3 REQUIRED)
set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR})

#============================================================================
# Search for project-specific dependencies
#============================================================================

#--------------------------------------
# Find gz-sim
gz_find_package(gz-sim7 REQUIRED)
set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR})

#--------------------------------------
# Find RapidJSON
# --------------------------------------------------------------------------- #
# Find RapidJSON.
find_package(RapidJSON REQUIRED)

#======================================
# Build plugin
# --------------------------------------------------------------------------- #
# Build plugin.

add_library(ArduPilotPlugin
SHARED
src/ArduPilotPlugin.cc
src/Socket.cpp
src/Util.cc
)
target_include_directories(ArduPilotPlugin PUBLIC
target_include_directories(ArduPilotPlugin PRIVATE
include
${GZ-SIM_INCLUDE_DIRS}
)
target_link_libraries(ArduPilotPlugin PUBLIC
${GZ-SIM_LIBRARIES}
target_link_libraries(ArduPilotPlugin PRIVATE
gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
)

add_library(ParachutePlugin
SHARED
src/ParachutePlugin.cc
)
target_include_directories(ParachutePlugin PUBLIC
target_include_directories(ParachutePlugin PRIVATE
include
${GZ-SIM_INCLUDE_DIRS}
)
target_link_libraries(ParachutePlugin PRIVATE
gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
)

# --------------------------------------------------------------------------- #
# Install.

install(
TARGETS
ArduPilotPlugin
ParachutePlugin
DESTINATION lib/${PROJECT_NAME}
)

install(
DIRECTORY
config/
DESTINATION share/${PROJECT_NAME}/config
)

install(
DIRECTORY
models/
DESTINATION share/${PROJECT_NAME}/models
)

install(
DIRECTORY
worlds/
DESTINATION share/${PROJECT_NAME}/worlds
)

# --------------------------------------------------------------------------- #
# Register as an ament package if ament_cmake is available.
if(${ament_cmake_FOUND})
ament_environment_hooks(
"${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in")
ament_environment_hooks(
"${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.sh.in")

target_link_libraries(ParachutePlugin PUBLIC
${GZ-SIM_LIBRARIES}
)
ament_package()
endif()
4 changes: 4 additions & 0 deletions hooks/ardupilot_gazebo.dsv.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share;@CMAKE_INSTALL_PREFIX@/share
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/@PROJECT_NAME@/models
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/@PROJECT_NAME@/worlds
prepend-non-duplicate;GZ_SIM_SYSTEM_PLUGIN_PATH;lib/@PROJECT_NAME@/
3 changes: 3 additions & 0 deletions hooks/ardupilot_gazebo.sh.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ament_prepend_unique_value GZ_SIM_RESOURCE_PATH "$AMENT_CURRENT_PREFIX/share/@PROJECT_NAME@/models"
ament_prepend_unique_value GZ_SIM_RESOURCE_PATH "$AMENT_CURRENT_PREFIX/share/@PROJECT_NAME@/worlds"
ament_prepend_unique_value GZ_SIM_PLUGIN_PATH "$AMENT_CURRENT_PREFIX/lib/@PROJECT_NAME@"
23 changes: 23 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ardupilot_gazebo</name>
<version>0.0.0</version>
<description>Plugins and models for vehicle simulation in Gazebo Sim with ArduPilot SITL controllers</description>
<maintainer email="rhys.mainwaring@me.com">Rhys Mainwaring</maintainer>
<license>GPL-3.0</license>
<author>Rhys Mainwaring</author>

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

<test_depend>ament_lint_auto</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>

0 comments on commit a739479

Please sign in to comment.