From a92b39daf37a63dc3482e2934e01ae9a7bc3211f Mon Sep 17 00:00:00 2001 From: Tobias Fischer Date: Wed, 1 May 2024 13:53:25 +1000 Subject: [PATCH] Update ros-humble-nav2-waypoint-follower.patch --- patch/ros-humble-nav2-waypoint-follower.patch | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/patch/ros-humble-nav2-waypoint-follower.patch b/patch/ros-humble-nav2-waypoint-follower.patch index 79eda654..68f22e5b 100644 --- a/patch/ros-humble-nav2-waypoint-follower.patch +++ b/patch/ros-humble-nav2-waypoint-follower.patch @@ -12,10 +12,10 @@ index a3b46942b..e228086fa 100644 find_package(OpenCV 4 QUIET) if(NOT OpenCV_FOUND) -diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp +diff --git a/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp b/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp index 9c46fdf1f8..1e6048aefc 100644 ---- a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp -+++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp +--- a/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp ++++ b/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp @@ -32,8 +32,8 @@ #include "sensor_msgs/msg/image.hpp"