diff --git a/.travis.sh b/.travis.sh
index 8b1037ef0..4fa96c4cf 100755
--- a/.travis.sh
+++ b/.travis.sh
@@ -29,11 +29,11 @@ travis_time_start setup.before_install
#before_install:
# Define some config vars.
# Install ROS
-sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
+sudo sh -c 'echo "deb http://repositories.ros.org/ubuntu/testing $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
sudo apt-get update -qq || echo Ignore error on apt-get update
# Install ROS
-sudo apt-get install -qq -y python-catkin-pkg python-catkin-tools python-rosdep python-wstool ros-$ROS_DISTRO-catkin
+sudo apt-get install -qq -y python3-catkin-pkg python3-catkin-tools python3-rosdep python3-wstool ros-$ROS_DISTRO-catkin
source /opt/ros/$ROS_DISTRO/setup.bash
# Setup for rosdep
sudo rosdep init
diff --git a/.travis.yml b/.travis.yml
index 19e599e88..aa3adcde3 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -2,7 +2,7 @@ sudo: required
dist: trusty
language: generic
env:
- - ROS_DISTRO=melodic
+ - ROS_DISTRO=noetic
# Install system dependencies, namely ROS.
before_install:
# Define some config vars.
@@ -11,7 +11,7 @@ before_install:
- export ROS_PARALLEL_JOBS='-j8 -l6'
script:
- echo "Testing branch $TRAVIS_BRANCH of $REPOSITORY_NAME"
- - docker run --rm -i -v $CI_SOURCE_PATH:$CI_SOURCE_PATH -e "CI_SOURCE_PATH=$CI_SOURCE_PATH" -e "HOME=$HOME" -e "ROS_DISTRO=$ROS_DISTRO" -e "ROS_PARALLEL_JOBS=$ROS_PARALLEL_JOBS" -t ubuntu:bionic sh -c "cd $CI_SOURCE_PATH; ./.travis.sh"
+ - docker run --rm -i -v $CI_SOURCE_PATH:$CI_SOURCE_PATH -e "CI_SOURCE_PATH=$CI_SOURCE_PATH" -e "HOME=$HOME" -e "ROS_DISTRO=$ROS_DISTRO" -e "ROS_PARALLEL_JOBS=$ROS_PARALLEL_JOBS" -t ubuntu:focal sh -c "cd $CI_SOURCE_PATH; ./.travis.sh"
after_failure:
- find ${HOME}/.ros/test_results -type f -exec echo "== {} ==" \; -exec cat {} \;
- for file in ${HOME}/.ros/log/rostest-*; do echo "=== $file ==="; cat $file; done
diff --git a/cv_bridge/CMakeLists.txt b/cv_bridge/CMakeLists.txt
index 997bef3e1..51089cbe3 100644
--- a/cv_bridge/CMakeLists.txt
+++ b/cv_bridge/CMakeLists.txt
@@ -1,19 +1,15 @@
-cmake_minimum_required(VERSION 2.8)
+cmake_minimum_required(VERSION 3.0.2)
project(cv_bridge)
find_package(catkin REQUIRED COMPONENTS rosconsole sensor_msgs)
if(NOT ANDROID)
find_package(PythonLibs)
- if(PYTHONLIBS_VERSION_STRING VERSION_LESS 3)
- find_package(Boost REQUIRED python)
- else()
- find_package(Boost REQUIRED python3)
- endif()
+ find_package(Boost REQUIRED python)
else()
find_package(Boost REQUIRED)
endif()
-find_package(OpenCV 3 REQUIRED
+find_package(OpenCV 4 REQUIRED
COMPONENTS
opencv_core
opencv_imgproc
diff --git a/cv_bridge/package.xml b/cv_bridge/package.xml
index e2dae4cdc..63d9f765f 100644
--- a/cv_bridge/package.xml
+++ b/cv_bridge/package.xml
@@ -21,21 +21,21 @@
boost
libopencv-dev
- python
- python-opencv
+ python3
+ python3-opencv
rosconsole
sensor_msgs
boost
libopencv-dev
- python
- python-opencv
+ python3
+ python3-opencv
rosconsole
libopencv-dev
sensor_msgs
rostest
- python-numpy
+ python3-numpy
dvipng
diff --git a/cv_bridge/python/cv_bridge/core.py b/cv_bridge/python/cv_bridge/core.py
index a47bbd764..5d221b54e 100644
--- a/cv_bridge/python/cv_bridge/core.py
+++ b/cv_bridge/python/cv_bridge/core.py
@@ -167,8 +167,12 @@ def imgmsg_to_cv2(self, img_msg, desired_encoding = "passthrough"):
im = np.ndarray(shape=(img_msg.height, img_msg.width),
dtype=dtype, buffer=img_msg.data)
else:
- im = np.ndarray(shape=(img_msg.height, img_msg.width, n_channels),
- dtype=dtype, buffer=img_msg.data)
+ if(type(img_msg.data) == str):
+ im = np.ndarray(shape=(img_msg.height, img_msg.width, n_channels),
+ dtype=dtype, buffer=img_msg.data.encode())
+ else:
+ im = np.ndarray(shape=(img_msg.height, img_msg.width, n_channels),
+ dtype=dtype, buffer=img_msg.data)
# If the byt order is different between the message and the system.
if img_msg.is_bigendian == (sys.byteorder == 'little'):
im = im.byteswap().newbyteorder()
diff --git a/cv_bridge/setup.py b/cv_bridge/setup.py
index 65ae95d67..f8812a205 100644
--- a/cv_bridge/setup.py
+++ b/cv_bridge/setup.py
@@ -1,5 +1,5 @@
#!/usr/bin/env python
-from distutils.core import setup
+from setuptools import setup
from catkin_pkg.python_setup import generate_distutils_setup
d = generate_distutils_setup()
diff --git a/cv_bridge/src/CMakeLists.txt b/cv_bridge/src/CMakeLists.txt
index d5d8ee223..55a4c3027 100644
--- a/cv_bridge/src/CMakeLists.txt
+++ b/cv_bridge/src/CMakeLists.txt
@@ -32,11 +32,7 @@ if (PYTHON_VERSION_MAJOR VERSION_EQUAL 3)
add_definitions(-DPYTHON3)
endif()
-if (OpenCV_VERSION_MAJOR VERSION_EQUAL 3)
-add_library(${PROJECT_NAME}_boost module.cpp module_opencv3.cpp)
-else()
-add_library(${PROJECT_NAME}_boost module.cpp module_opencv2.cpp)
-endif()
+add_library(${PROJECT_NAME}_boost module.cpp module_opencv4.cpp)
target_link_libraries(${PROJECT_NAME}_boost ${Boost_LIBRARIES}
${catkin_LIBRARIES}
${PYTHON_LIBRARIES}
diff --git a/cv_bridge/src/module.hpp b/cv_bridge/src/module.hpp
index 92153ac80..aa8b5f6c5 100644
--- a/cv_bridge/src/module.hpp
+++ b/cv_bridge/src/module.hpp
@@ -33,16 +33,10 @@ int convert_to_CvMat2(const PyObject* o, cv::Mat& m);
PyObject* pyopencv_from(const cv::Mat& m);
-#if PYTHON3
-static int do_numpy_import( )
+static void * do_numpy_import( )
{
import_array( );
+ return nullptr;
}
-#else
-static void do_numpy_import( )
-{
- import_array( );
-}
-#endif
#endif
diff --git a/cv_bridge/src/module_opencv2.cpp b/cv_bridge/src/module_opencv2.cpp
deleted file mode 100644
index 9f0752bed..000000000
--- a/cv_bridge/src/module_opencv2.cpp
+++ /dev/null
@@ -1,262 +0,0 @@
-/*********************************************************************
-* Software License Agreement (BSD License)
-*
-* Copyright (c) 2012, Willow Garage, Inc.
-* All rights reserved.
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-*
-* * Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* * Redistributions in binary form must reproduce the above
-* copyright notice, this list of conditions and the following
-* disclaimer in the documentation and/or other materials provided
-* with the distribution.
-* * Neither the name of the Willow Garage nor the names of its
-* contributors may be used to endorse or promote products derived
-* from this software without specific prior written permission.
-*
-* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-* POSSIBILITY OF SUCH DAMAGE.
-*********************************************************************/
-
-#include "module.hpp"
-
-using namespace cv;
-
-// These are sucky, sketchy versions of the real things in OpenCV Python,
-// inferior in every way.
-
-static int failmsg(const char *fmt, ...)
-{
- char str[1000];
-
- va_list ap;
- va_start(ap, fmt);
- vsnprintf(str, sizeof(str), fmt, ap);
- va_end(ap);
-
- PyErr_SetString(PyExc_TypeError, str);
- return 0;
-}
-
-static PyObject* opencv_error = 0;
-
-class PyAllowThreads
-{
-public:
- PyAllowThreads() : _state(PyEval_SaveThread()) {}
- ~PyAllowThreads()
- {
- PyEval_RestoreThread(_state);
- }
-private:
- PyThreadState* _state;
-};
-
-#define ERRWRAP2(expr) \
-try \
-{ \
- PyAllowThreads allowThreads; \
- expr; \
-} \
-catch (const cv::Exception &e) \
-{ \
- PyErr_SetString(opencv_error, e.what()); \
- return 0; \
-}
-
-// Taken from http://stackoverflow.com/questions/19136944/call-c-opencv-functions-from-python-send-a-cv-mat-to-c-dll-which-is-usi
-
-
-static size_t REFCOUNT_OFFSET = ( size_t )&((( PyObject* )0)->ob_refcnt ) +
-( 0x12345678 != *( const size_t* )"\x78\x56\x34\x12\0\0\0\0\0" )*sizeof( int );
-
-
-static inline PyObject* pyObjectFromRefcount( const int* refcount )
-{
-return ( PyObject* )(( size_t )refcount - REFCOUNT_OFFSET );
-}
-
-static inline int* refcountFromPyObject( const PyObject* obj )
-{
-return ( int* )(( size_t )obj + REFCOUNT_OFFSET );
-}
-
-class NumpyAllocator : public cv::MatAllocator
-{
-public:
-NumpyAllocator( ) { }
-~NumpyAllocator( ) { }
-
-void allocate( int dims, const int* sizes, int type, int*& refcount,
-uchar*& datastart, uchar*& data, size_t* step );
-
-void deallocate( int* refcount, uchar* datastart, uchar* data );
-};
-
-void NumpyAllocator::allocate( int dims, const int* sizes, int type, int*& refcount, uchar*& datastart, uchar*& data, size_t* step )
-{
- int depth = CV_MAT_DEPTH( type );
- int cn = CV_MAT_CN( type );
- const int f = ( int )( sizeof( size_t )/8 );
- int typenum = depth == CV_8U ? NPY_UBYTE : depth == CV_8S ? NPY_BYTE :
- depth == CV_16U ? NPY_USHORT : depth == CV_16S ? NPY_SHORT :
- depth == CV_32S ? NPY_INT : depth == CV_32F ? NPY_FLOAT :
- depth == CV_64F ? NPY_DOUBLE : f*NPY_ULONGLONG + (f^1)*NPY_UINT;
- int i;
- npy_intp _sizes[CV_MAX_DIM+1];
- for( i = 0; i < dims; i++ )
- _sizes[i] = sizes[i];
- if( cn > 1 )
- {
- /*if( _sizes[dims-1] == 1 )
- _sizes[dims-1] = cn;
- else*/
- _sizes[dims++] = cn;
- }
- PyObject* o = PyArray_SimpleNew( dims, _sizes, typenum );
- if( !o )
- CV_Error_(CV_StsError, ("The numpy array of typenum=%d, ndims=%d can not be created", typenum, dims));
- refcount = refcountFromPyObject(o);
- npy_intp* _strides = PyArray_STRIDES((PyArrayObject*) o);
- for( i = 0; i < dims - (cn > 1); i++ )
- step[i] = (size_t)_strides[i];
- datastart = data = (uchar*)PyArray_DATA((PyArrayObject*)o);
-
-}
-
-void NumpyAllocator::deallocate( int* refcount, uchar* datastart, uchar* data )
-{
- if( !refcount )
- return;
- PyObject* o = pyObjectFromRefcount(refcount);
- Py_INCREF(o);
- Py_DECREF(o);
-}
-
-// Declare the object
-NumpyAllocator g_numpyAllocator;
-
-int convert_to_CvMat2(const PyObject* o, cv::Mat& m)
-{
- // to avoid PyArray_Check() to crash even with valid array
- do_numpy_import();
-
- if(!o || o == Py_None)
- {
- if( !m.data )
- m.allocator = &g_numpyAllocator;
- return true;
- }
-
- if( !PyArray_Check(o) )
- {
- failmsg("Not a numpy array");
- return false;
- }
-
- // NPY_LONG (64 bit) is converted to CV_32S (32 bit)
- int typenum = PyArray_TYPE((PyArrayObject*) o);
- int type = typenum == NPY_UBYTE ? CV_8U : typenum == NPY_BYTE ? CV_8S :
- typenum == NPY_USHORT ? CV_16U : typenum == NPY_SHORT ? CV_16S :
- typenum == NPY_INT || typenum == NPY_LONG ? CV_32S :
- typenum == NPY_FLOAT ? CV_32F :
- typenum == NPY_DOUBLE ? CV_64F : -1;
-
- if( type < 0 )
- {
- failmsg("data type = %d is not supported", typenum);
- return false;
- }
-
- int ndims = PyArray_NDIM((PyArrayObject*) o);
- if(ndims >= CV_MAX_DIM)
- {
- failmsg("dimensionality (=%d) is too high", ndims);
- return false;
- }
-
- int size[CV_MAX_DIM+1];
- size_t step[CV_MAX_DIM+1], elemsize = CV_ELEM_SIZE1(type);
- const npy_intp* _sizes = PyArray_DIMS((PyArrayObject*) o);
- const npy_intp* _strides = PyArray_STRIDES((PyArrayObject*) o);
- bool transposed = false;
-
- for(int i = 0; i < ndims; i++)
- {
- size[i] = (int)_sizes[i];
- step[i] = (size_t)_strides[i];
- }
-
- if( ndims == 0 || step[ndims-1] > elemsize ) {
- size[ndims] = 1;
- step[ndims] = elemsize;
- ndims++;
- }
-
- if( ndims >= 2 && step[0] < step[1] )
- {
- std::swap(size[0], size[1]);
- std::swap(step[0], step[1]);
- transposed = true;
- }
-
- if( ndims == 3 && size[2] <= CV_CN_MAX && step[1] == elemsize*size[2] )
- {
- ndims--;
- type |= CV_MAKETYPE(0, size[2]);
- }
-
- if( ndims > 2 )
- {
- failmsg("more than 2 dimensions");
- return false;
- }
-
- m = cv::Mat(ndims, size, type, PyArray_DATA((PyArrayObject*) o), step);
-
- if( m.data )
- {
- m.refcount = refcountFromPyObject(o);
- m.addref(); // protect the original numpy array from deallocation
- // (since Mat destructor will decrement the reference counter)
- };
- m.allocator = &g_numpyAllocator;
-
- if( transposed )
- {
- cv::Mat tmp;
- tmp.allocator = &g_numpyAllocator;
- transpose(m, tmp);
- m = tmp;
- }
- return true;
-}
-
-PyObject* pyopencv_from(const Mat& m)
-{
- if( !m.data )
- Py_RETURN_NONE;
- Mat temp, *p = (Mat*)&m;
- if(!p->refcount || p->allocator != &g_numpyAllocator)
- {
- temp.allocator = &g_numpyAllocator;
- ERRWRAP2(m.copyTo(temp));
- p = &temp;
- }
- p->addref();
- return pyObjectFromRefcount(p->refcount);
-}
diff --git a/cv_bridge/src/module_opencv3.cpp b/cv_bridge/src/module_opencv4.cpp
similarity index 98%
rename from cv_bridge/src/module_opencv3.cpp
rename to cv_bridge/src/module_opencv4.cpp
index 68c1b2007..fe2b677c8 100644
--- a/cv_bridge/src/module_opencv3.cpp
+++ b/cv_bridge/src/module_opencv4.cpp
@@ -107,7 +107,7 @@ class NumpyAllocator : public MatAllocator
return u;
}
- UMatData* allocate(int dims0, const int* sizes, int type, void* data, size_t* step, int flags, UMatUsageFlags usageFlags) const
+ UMatData* allocate(int dims0, const int* sizes, int type, void* data, size_t* step, AccessFlag flags, UMatUsageFlags usageFlags) const
{
if( data != 0 )
{
@@ -136,7 +136,7 @@ class NumpyAllocator : public MatAllocator
return allocate(o, dims0, sizes, type, step);
}
- bool allocate(UMatData* u, int accessFlags, UMatUsageFlags usageFlags) const
+ bool allocate(UMatData* u, AccessFlag accessFlags, UMatUsageFlags usageFlags) const
{
return stdAllocator->allocate(u, accessFlags, usageFlags);
}
diff --git a/cv_bridge/test/conversions.py b/cv_bridge/test/conversions.py
index bde1380f3..a01ed5e28 100644
--- a/cv_bridge/test/conversions.py
+++ b/cv_bridge/test/conversions.py
@@ -49,7 +49,7 @@ def test_encode_decode_cv2_compressed(self):
# from: http://docs.opencv.org/2.4/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags)
# NOTE: remove jp2(a.k.a JPEG2000) as its JASPER codec is disabled within Ubuntu opencv library
# due to security issues, but it works once you rebuild your opencv library with JASPER enabled
- formats = ["jpg", "jpeg", "jpe", "png", "bmp", "dib", "ppm", "pgm", "pbm",
+ formats = ["jpg", "jpeg", "jpe", "png", "bmp", "dib",
"sr", "ras", "tif", "tiff"] # this formats rviz is not support
cvb_en = CvBridge()
@@ -63,6 +63,7 @@ def test_encode_decode_cv2_compressed(self):
original = np.uint8(np.random.randint(0, 255, size=(h, w)))
else:
original = np.uint8(np.random.randint(0, 255, size=(h, w, channels)))
+ print(f)
compress_rosmsg = cvb_en.cv2_to_compressed_imgmsg(original, f)
newimg = cvb_de.compressed_imgmsg_to_cv2(compress_rosmsg)
self.assert_(original.dtype == newimg.dtype)
diff --git a/cv_bridge/test/enumerants.py b/cv_bridge/test/enumerants.py
index bdcc7a8ef..dbb336325 100644
--- a/cv_bridge/test/enumerants.py
+++ b/cv_bridge/test/enumerants.py
@@ -22,7 +22,7 @@ def test_enumerants_cv2(self):
bridge_ = CvBridge()
cvim = bridge_.imgmsg_to_cv2(img_msg, "rgb8")
import sys
- self.assertRaises(sys.getrefcount(cvim) == 2)
+ self.assert_(sys.getrefcount(cvim) == 2)
# A 3 channel image cannot be sent as an rgba8
self.assertRaises(CvBridgeError, lambda: bridge_.cv2_to_imgmsg(cvim, "rgba8"))
@@ -31,9 +31,9 @@ def test_enumerants_cv2(self):
bridge_.cv2_to_imgmsg(cvim, "rgb8")
bridge_.cv2_to_imgmsg(cvim, "bgr8")
- self.assertRaises(getCvType("32FC4") == cv2.CV_8UC4)
- self.assertRaises(getCvType("8UC1") == cv2.CV_8UC1)
- self.assertRaises(getCvType("8U") == cv2.CV_8UC1)
+ self.assert_(getCvType("32FC4") == cv2.CV_32FC4)
+ self.assert_(getCvType("8UC1") == cv2.CV_8UC1)
+ self.assert_(getCvType("8U") == cv2.CV_8UC1)
def test_numpy_types(self):
import cv2
diff --git a/cv_bridge/test/python_bindings.py b/cv_bridge/test/python_bindings.py
index 6dd320905..3d94f4e56 100644
--- a/cv_bridge/test/python_bindings.py
+++ b/cv_bridge/test/python_bindings.py
@@ -10,15 +10,15 @@ def test_cvtColorForDisplay():
height, width = label.shape[:2]
label_value = 0
grid_num_y, grid_num_x = 3, 4
- for grid_row in xrange(grid_num_y):
+ for grid_row in range(grid_num_y):
grid_size_y = height / grid_num_y
min_y = grid_size_y * grid_row
max_y = min_y + grid_size_y
- for grid_col in xrange(grid_num_x):
+ for grid_col in range(grid_num_x):
grid_size_x = width / grid_num_x
min_x = grid_size_x * grid_col
max_x = min_x + grid_size_x
- label[min_y:max_y, min_x:max_x] = label_value
+ label[int(min_y):int(max_y), int(min_x):int(max_x)] = label_value
label_value += 1
label_viz = cv_bridge.cvtColorForDisplay(label, '32SC1', 'bgr8')
assert_equal(label_viz.dtype, np.uint8)
diff --git a/image_geometry/CMakeLists.txt b/image_geometry/CMakeLists.txt
index 6c2274192..7eac069fd 100644
--- a/image_geometry/CMakeLists.txt
+++ b/image_geometry/CMakeLists.txt
@@ -1,4 +1,4 @@
-cmake_minimum_required(VERSION 2.8)
+cmake_minimum_required(VERSION 3.0.2)
project(image_geometry)
find_package(catkin REQUIRED sensor_msgs)
diff --git a/image_geometry/setup.py b/image_geometry/setup.py
index 407ce1e5e..3a52c4bd3 100644
--- a/image_geometry/setup.py
+++ b/image_geometry/setup.py
@@ -1,5 +1,5 @@
#!/usr/bin/env python
-from distutils.core import setup
+from setuptools import setup
from catkin_pkg.python_setup import generate_distutils_setup
d = generate_distutils_setup()
diff --git a/opencv_tests/CMakeLists.txt b/opencv_tests/CMakeLists.txt
index b45ba8c77..6b4d2a7ce 100644
--- a/opencv_tests/CMakeLists.txt
+++ b/opencv_tests/CMakeLists.txt
@@ -1,4 +1,4 @@
-cmake_minimum_required(VERSION 2.8)
+cmake_minimum_required(VERSION 3.0.2)
project(opencv_tests)
find_package(catkin REQUIRED)
diff --git a/opencv_tests/launch/pong.launch b/opencv_tests/launch/pong.launch
index c57124337..b8038b416 100644
--- a/opencv_tests/launch/pong.launch
+++ b/opencv_tests/launch/pong.launch
@@ -1,5 +1,5 @@
-
-
+
+
diff --git a/opencv_tests/nodes/broadcast.py b/opencv_tests/nodes/broadcast.py
index 0df824dbb..f0290f84d 100755
--- a/opencv_tests/nodes/broadcast.py
+++ b/opencv_tests/nodes/broadcast.py
@@ -70,7 +70,7 @@ def main(args):
rospy.spin()
outcome = 'test completed'
except KeyboardInterrupt:
- print "shutting down"
+ print("shutting down")
outcome = 'keyboard interrupt'
rospy.core.signal_shutdown(outcome)
diff --git a/opencv_tests/nodes/source.py b/opencv_tests/nodes/source.py
index 4662fbef8..e4c2bfedc 100755
--- a/opencv_tests/nodes/source.py
+++ b/opencv_tests/nodes/source.py
@@ -87,7 +87,7 @@ def main(args):
rospy.spin()
outcome = 'test completed'
except KeyboardInterrupt:
- print "shutting down"
+ print("shutting down")
outcome = 'keyboard interrupt'
rospy.core.signal_shutdown(outcome)
diff --git a/vision_opencv/CMakeLists.txt b/vision_opencv/CMakeLists.txt
index 8f1965de2..c5742e30f 100644
--- a/vision_opencv/CMakeLists.txt
+++ b/vision_opencv/CMakeLists.txt
@@ -1,4 +1,4 @@
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 3.0.2)
project(vision_opencv)
find_package(catkin REQUIRED)
catkin_metapackage()