Skip to content

Commit

Permalink
Update to yaml-cpp 0.8.0 (#1183)
Browse files Browse the repository at this point in the history
yaml-cpp 0.8.0 has a proper CMake target, i.e. yaml-cpp::yaml-cpp.
Use that here.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Apr 11, 2024
1 parent 8b95db4 commit 4bea9a4
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ find_package(tf2_ros REQUIRED)
find_package(message_filters REQUIRED)
find_package(urdf REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
find_package(yaml-cpp REQUIRED)

find_package(TinyXML2 REQUIRED) # provided by tinyxml2_vendor

Expand Down Expand Up @@ -248,7 +249,7 @@ target_link_libraries(rviz_common PUBLIC
${std_srvs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
yaml-cpp
yaml-cpp::yaml-cpp
)

target_link_libraries(rviz_common PRIVATE
Expand All @@ -274,6 +275,7 @@ ament_export_dependencies(
tf2
tf2_ros
yaml_cpp_vendor
yaml-cpp
)

# Export old-style CMake variables
Expand Down Expand Up @@ -443,7 +445,7 @@ if(BUILD_TESTING)
test/mock_property_change_receiver.cpp
${SKIP_DISPLAY_TESTS})
if(TARGET rviz_common_display_test)
target_link_libraries(rviz_common_display_test rviz_common Qt5::Widgets yaml-cpp)
target_link_libraries(rviz_common_display_test rviz_common Qt5::Widgets yaml-cpp::yaml-cpp)
endif()
endif()

Expand Down

0 comments on commit 4bea9a4

Please sign in to comment.