Skip to content

Commit

Permalink
Move xmlrpcpp find_package so it only searches if ROS 1 is found
Browse files Browse the repository at this point in the history
Signed-off-by: Geoffrey Biggs <gbiggs@killbots.net>
  • Loading branch information
gbiggs committed Jul 18, 2022
1 parent 4af421d commit 86b4245
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rmw_implementation_cmake REQUIRED)
find_package(std_msgs REQUIRED)
find_package(xmlrpcpp REQUIRED)

# find ROS 1 packages
set(cmake_extras_files cmake/find_ros1_package.cmake cmake/find_ros1_interface_packages.cmake)
Expand Down Expand Up @@ -45,6 +44,10 @@ endif()

find_ros1_package(std_msgs REQUIRED)

# Dependency that we should only look for if ROS 1 is installed (it's not present on a ROS 2
# system; see https://github.com/ros2/ros1_bridge/pull/331#issuecomment-1188111510)
find_package(xmlrpcpp REQUIRED)

# find ROS 1 packages with messages / services
include(cmake/find_ros1_interface_packages.cmake)
find_ros1_interface_packages(ros1_message_packages)
Expand Down

0 comments on commit 86b4245

Please sign in to comment.