summarylogtreecommitdiffstats
path: root/opencv-header.patch
diff options
context:
space:
mode:
authorBen Wolsieffer2019-02-02 00:16:29 -0500
committerBen Wolsieffer2019-02-02 00:16:29 -0500
commitd3bbe0dbe942cafb99cc5523a70a9773a1b61d12 (patch)
treeca3f62eba9b7eaced1ecb03404fcc5809377aae1 /opencv-header.patch
parent24a0c332fe8c9788dbe741e6d925dacedb246731 (diff)
downloadaur-ros-kinetic-gazebo-plugins.tar.gz
2.5.14 -> 2.5.18
Diffstat (limited to 'opencv-header.patch')
-rw-r--r--opencv-header.patch28
1 files changed, 28 insertions, 0 deletions
diff --git a/opencv-header.patch b/opencv-header.patch
new file mode 100644
index 000000000000..816432c36411
--- /dev/null
+++ b/opencv-header.patch
@@ -0,0 +1,28 @@
+From 3819c073c74667996359e6a4ac9d8e8f477fedc1 Mon Sep 17 00:00:00 2001
+From: Ben Wolsieffer <benwolsieffer@gmail.com>
+Date: Sat, 2 Feb 2019 00:09:45 -0500
+Subject: [PATCH] Remove old OpenCV header.
+
+---
+ gazebo_plugins/src/gazebo_ros_prosilica.cpp | 5 +----
+ 1 file changed, 1 insertion(+), 4 deletions(-)
+
+diff --git a/gazebo_plugins/src/gazebo_ros_prosilica.cpp b/gazebo_plugins/src/gazebo_ros_prosilica.cpp
+index cb25c41..9fee4b3 100644
+--- a/gazebo_plugins/src/gazebo_ros_prosilica.cpp
++++ b/gazebo_plugins/src/gazebo_ros_prosilica.cpp
+@@ -44,10 +44,7 @@
+ #include <diagnostic_updater/diagnostic_updater.h>
+ #include <sensor_msgs/RegionOfInterest.h>
+
+-#include <opencv/cv.h>
+-#include <opencv/highgui.h>
+-
+-#include <opencv/cvwimage.h>
++#include <opencv2/opencv.hpp>
+
+ #include <boost/scoped_ptr.hpp>
+ #include <boost/bind.hpp>
+--
+2.20.1
+