From b3cc9ed55e1510b253af7b126ff1ab5f19b47828 Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 13:35:05 +0300 Subject: [PATCH 1/7] package.xml: Add conditional python3 dependencies --- cv_bridge/package.xml | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/cv_bridge/package.xml b/cv_bridge/package.xml index e2dae4cdc..7a9cad93f 100644 --- a/cv_bridge/package.xml +++ b/cv_bridge/package.xml @@ -1,4 +1,4 @@ - + cv_bridge 1.13.0 @@ -21,21 +21,26 @@ boost libopencv-dev - python - python-opencv + python + python3 + python-opencv + python3-opencv rosconsole sensor_msgs boost libopencv-dev - python - python-opencv + python + python3 + python-opencv + python3-opencv rosconsole libopencv-dev sensor_msgs rostest - python-numpy + python-numpy + python3-numpy dvipng From 661a7b9bc5886a04e88e39e14196d142a4d584b9 Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 17:04:59 +0300 Subject: [PATCH 2/7] travis: Build for Python 3 --- .travis.sh | 43 +++++++++++++++++++++++++++++++++++++------ .travis.yml | 5 +++-- 2 files changed, 40 insertions(+), 8 deletions(-) diff --git a/.travis.sh b/.travis.sh index 8b1037ef0..e9a3be8e5 100755 --- a/.travis.sh +++ b/.travis.sh @@ -33,11 +33,38 @@ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main 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 -source /opt/ros/$ROS_DISTRO/setup.bash -# Setup for rosdep -sudo rosdep init -rosdep update +if [ "x${ROS_PYTHON_VERSION}" == "x3" ]; then + sudo apt-get install -qq -y python3-catkin-pkg python3-rosdep python3-rosinstall-generator python3-wstool python3-vcstool build-essential + wget https://bootstrap.pypa.io/get-pip.py + python3 ./get-pip.py + rm ./get-pip.py + pip3 install catkin_tools + # Update rosdep definitions + sudo rosdep init + rosdep update + # Create an underlay with all dependencies + mkdir -p ~/underlay_ws/src + cd ~/underlay_ws + # FIXME: use RPP instead of hardcoded list? + # FIXME: change --upstream-devel to releases? + rosinstall_generator cv_bridge image_geometry --deps --deps-only --upstream-devel --rosdistro $ROS_DISTRO > deps.rosinstall + vcs import --input deps.rosinstall ./src + # FIXME: roslisp does not get pulled somehow + if [ ! -d "./src/roslisp" ]; then + git clone https://github.com/ros/roslisp src/roslisp + fi + rosdep install --from-paths ./src --ignore-src -y + catkin config --install --cmake-args -DCMAKE_BUILD_TYPE=Release + catkin build + source ~/underlay_ws/install/setup.bash +else + sudo apt-get install -qq -y python-catkin-pkg python-catkin-tools python-rosdep python-wstool ros-$ROS_DISTRO-catkin + source /opt/ros/$ROS_DISTRO/setup.bash + # Setup for rosdep + sudo rosdep init + rosdep update +fi + travis_time_end travis_time_start setup.install @@ -67,7 +94,11 @@ travis_time_end travis_time_start setup.script # Compile and test. #script: -source /opt/ros/$ROS_DISTRO/setup.bash +if [ "x${ROS_PYTHON_VERSION}" == "x3" ]; then + source ~/underlay_ws/install/setup.bash +else + source /opt/ros/$ROS_DISTRO/setup.bash +fi cd ~/catkin_ws catkin build -p1 -j1 --no-status catkin run_tests -p1 -j1 diff --git a/.travis.yml b/.travis.yml index 19e599e88..250f51467 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,7 +2,8 @@ sudo: required dist: trusty language: generic env: - - ROS_DISTRO=melodic + - ROS_DISTRO=melodic ROS_PYTHON_VERSION=2 + - ROS_DISTRO=melodic ROS_PYTHON_VERSION=3 # Install system dependencies, namely ROS. before_install: # Define some config vars. @@ -11,7 +12,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" -e "ROS_PYTHON_VERSION=$ROS_PYTHON_VERSION" -t ubuntu:bionic 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 From ce21a65bd0b4632e691c0adce20523327b745780 Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 17:25:58 +0300 Subject: [PATCH 3/7] cv_bridge: Add return to do_numpy_import, fix signature Newer compilers would optimize do_numpy_import() out due to not every path returning a value. Return type for this function should be a pointer (since the NUMPY_IMPORT_ARRAY_RETVAL in import_array() is NULL by default). --- cv_bridge/src/module.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/cv_bridge/src/module.hpp b/cv_bridge/src/module.hpp index 92153ac80..0d9fa411f 100644 --- a/cv_bridge/src/module.hpp +++ b/cv_bridge/src/module.hpp @@ -34,9 +34,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 NULL; } #else static void do_numpy_import( ) From 7511993cea15ab9ab8994cd258e3d6562c1c1635 Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 17:32:56 +0300 Subject: [PATCH 4/7] cv_bridge: Set `xrange = range` for Python 3 in tests --- cv_bridge/test/python_bindings.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cv_bridge/test/python_bindings.py b/cv_bridge/test/python_bindings.py index 6dd320905..83a43b859 100644 --- a/cv_bridge/test/python_bindings.py +++ b/cv_bridge/test/python_bindings.py @@ -3,6 +3,9 @@ import cv_bridge +import sys +if sys.version > '3': + xrange = range def test_cvtColorForDisplay(): # convert label image to display From 9051cbab4aed75e4a61d184f6ad341dd0f8f912f Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 17:47:54 +0300 Subject: [PATCH 5/7] cv_bridge: Use bytes in enumerants test --- cv_bridge/test/enumerants.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cv_bridge/test/enumerants.py b/cv_bridge/test/enumerants.py index bdcc7a8ef..e25c7f1f7 100644 --- a/cv_bridge/test/enumerants.py +++ b/cv_bridge/test/enumerants.py @@ -17,7 +17,7 @@ def test_enumerants_cv2(self): img_msg.height = 480 img_msg.encoding = "rgba8" img_msg.step = 640*4 - img_msg.data = (640 * 480) * "1234" + img_msg.data = (640 * 480) * b"1234" bridge_ = CvBridge() cvim = bridge_.imgmsg_to_cv2(img_msg, "rgb8") From 095143bba3012df14902135be9f8480c8a441c0b Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 18:07:24 +0300 Subject: [PATCH 6/7] cv_bridge: Wrap divisions in int() for tests --- cv_bridge/test/python_bindings.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cv_bridge/test/python_bindings.py b/cv_bridge/test/python_bindings.py index 83a43b859..7ab351a8b 100644 --- a/cv_bridge/test/python_bindings.py +++ b/cv_bridge/test/python_bindings.py @@ -14,11 +14,11 @@ def test_cvtColorForDisplay(): label_value = 0 grid_num_y, grid_num_x = 3, 4 for grid_row in xrange(grid_num_y): - grid_size_y = height / grid_num_y + grid_size_y = int(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): - grid_size_x = width / grid_num_x + grid_size_x = int(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 From 457af2fc5f9a407e7272b83348500cbc944926ba Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 28 Jan 2020 18:14:03 +0300 Subject: [PATCH 7/7] cv_bridge: Use correct assertions in enumerants test --- cv_bridge/test/enumerants.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/cv_bridge/test/enumerants.py b/cv_bridge/test/enumerants.py index e25c7f1f7..3e6772a96 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.assertTrue(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.assertFalse(getCvType("32FC4") == cv2.CV_8UC4) + self.assertTrue(getCvType("8UC1") == cv2.CV_8UC1) + self.assertTrue(getCvType("8U") == cv2.CV_8UC1) def test_numpy_types(self): import cv2