diff --git a/ros_gz_sim/CMakeLists.txt b/ros_gz_sim/CMakeLists.txt index 7f420e09..eb79bf94 100644 --- a/ros_gz_sim/CMakeLists.txt +++ b/ros_gz_sim/CMakeLists.txt @@ -12,6 +12,7 @@ endif() find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) +find_package(ros_gz_bridge REQUIRED) find_package(std_msgs REQUIRED) if(NOT DEFINED ENV{GZ_VERSION}) @@ -86,6 +87,22 @@ install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME} ) +# ROS Gz bridge +add_library(ros-gz-bridge-system SHARED src/ros_gz_bridge_system.cpp) +target_link_libraries(ros-gz-bridge-system PUBLIC + gz-sim${GZ_SIM_VER}::core + rclcpp::rclcpp + ros_gz_bridge::ros_gz_bridge +) +target_include_directories(ros-gz-bridge-system PUBLIC + "$" + "$" +) +install( + TARGETS ros-gz-bridge-system + DESTINATION lib +) + configure_file( launch/gz_sim.launch.py.in launch/gz_sim.launch.py.configured diff --git a/ros_gz_sim/package.xml b/ros_gz_sim/package.xml index a4cad906..bbad141a 100644 --- a/ros_gz_sim/package.xml +++ b/ros_gz_sim/package.xml @@ -17,6 +17,7 @@ ament_index_python libgflags-dev rclcpp + ros_gz_bridge std_msgs diff --git a/ros_gz_sim_demos/CMakeLists.txt b/ros_gz_sim_demos/CMakeLists.txt index 8e0f580a..d0626157 100644 --- a/ros_gz_sim_demos/CMakeLists.txt +++ b/ros_gz_sim_demos/CMakeLists.txt @@ -33,6 +33,12 @@ install( DESTINATION share/${PROJECT_NAME}/worlds ) +install( + DIRECTORY + config/ + DESTINATION share/${PROJECT_NAME}/config +) + ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in") ament_package() diff --git a/ros_gz_sim_demos/hooks/ros_gz_sim_demos.dsv.in b/ros_gz_sim_demos/hooks/ros_gz_sim_demos.dsv.in index a0c6d4fc..68a3bc14 100644 --- a/ros_gz_sim_demos/hooks/ros_gz_sim_demos.dsv.in +++ b/ros_gz_sim_demos/hooks/ros_gz_sim_demos.dsv.in @@ -1 +1 @@ -prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;@CMAKE_INSTALL_PREFIX@/share +prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;@CMAKE_INSTALL_PREFIX@/share