Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Noetic release #323

Merged
merged 10 commits into from
Apr 3, 2020
Merged
Show file tree
Hide file tree
Changes from 7 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .travis.sh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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
10 changes: 3 additions & 7 deletions cv_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand Down
8 changes: 6 additions & 2 deletions cv_bridge/python/cv_bridge/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
2 changes: 1 addition & 1 deletion cv_bridge/setup.py
Original file line number Diff line number Diff line change
@@ -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()
Expand Down
6 changes: 1 addition & 5 deletions cv_bridge/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}
Expand Down
7 changes: 0 additions & 7 deletions cv_bridge/src/module.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,16 +33,9 @@ int convert_to_CvMat2(const PyObject* o, cv::Mat& m);

PyObject* pyopencv_from(const cv::Mat& m);

#if PYTHON3
static int do_numpy_import( )
{
import_array( );
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
}
#else
static void do_numpy_import( )
{
import_array( );
}
#endif

#endif
262 changes: 0 additions & 262 deletions cv_bridge/src/module_opencv2.cpp

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -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 )
{
Expand Down Expand Up @@ -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);
}
Expand Down
Loading