diff --git a/rviz_common/CMakeLists.txt b/rviz_common/CMakeLists.txt
index 154e1f003..ee1969e88 100644
--- a/rviz_common/CMakeLists.txt
+++ b/rviz_common/CMakeLists.txt
@@ -53,7 +53,6 @@ find_package(tf2 REQUIRED)
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
@@ -286,7 +285,6 @@ ament_export_dependencies(
std_srvs
tf2
tf2_ros
- yaml_cpp_vendor
yaml-cpp
)
diff --git a/rviz_common/package.xml b/rviz_common/package.xml
index ef31a6469..1d32c39d1 100644
--- a/rviz_common/package.xml
+++ b/rviz_common/package.xml
@@ -51,7 +51,7 @@
message_filters
tinyxml2_vendor
urdf
- yaml_cpp_vendor
+ yaml-cpp
ament_lint_common
ament_cmake_gmock