diff --git a/patch/dependencies.yaml b/patch/dependencies.yaml index ad156fd1..c77cd9f9 100644 --- a/patch/dependencies.yaml +++ b/patch/dependencies.yaml @@ -264,3 +264,8 @@ wasm_cpp: aws_sdk_cpp_vendor: add_host: ["aws-sdk-cpp"] add_run: ["aws-sdk-cpp"] +polygon_rviz_plugins: + add_host: ["libgl-devel"] + add_run: ["libgl-devel"] +py_trees: + add_host: ["poetry-core"] diff --git a/patch/ros-humble-color-util.patch b/patch/ros-humble-color-util.patch new file mode 100644 index 00000000..c0696770 --- /dev/null +++ b/patch/ros-humble-color-util.patch @@ -0,0 +1,14 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index bc98189..71ce465 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -19,6 +19,9 @@ find_package(ament_cmake REQUIRED) + find_package(std_msgs REQUIRED) + + add_library(color_util src/convert.cpp) ++if(WIN32 AND MSVC) ++ set_target_properties(color_util PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() + target_include_directories(color_util PUBLIC + $ + $ diff --git a/patch/ros-humble-polygon-utils.patch b/patch/ros-humble-polygon-utils.patch new file mode 100644 index 00000000..8aa58ac4 --- /dev/null +++ b/patch/ros-humble-polygon-utils.patch @@ -0,0 +1,14 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index bc98189..71ce465 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -19,6 +19,9 @@ find_package(geometry_msgs REQUIRED) + find_package(polygon_msgs REQUIRED) + + add_library(polygon_utils src/polygon_utils.cpp) ++if(WIN32 AND MSVC) ++ set_target_properties(polygon_utils PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() + target_include_directories(polygon_utils PUBLIC + $ + $ diff --git a/vinca.yaml b/vinca.yaml index 95382eda..6a459336 100644 --- a/vinca.yaml +++ b/vinca.yaml @@ -315,6 +315,16 @@ packages_select_by_deps: - imu_tools - rplidar_ros - vector_pursuit_controller + - imu_transformer + - imu_calib + - polygon_msgs + - polygon_utils + - color_util + - rclc_parameter + - rclc_lifecycle + - rclc_examples + - ptz_action_server_msgs + - py_trees # These packages are only built on Linux as they depend on Linux-specific API - if: linux