Skip to content

Commit

Permalink
Noetic release image_common (#155)
Browse files Browse the repository at this point in the history
* noetic - Porting Python to Python3

Signed-off-by: ahcorde <[email protected]>

* Updated cmake_minimum_required to 3.0.2

Signed-off-by: ahcorde <[email protected]>

* changed diskutils.core for setuptools

Signed-off-by: ahcorde <[email protected]>

* ported to noetic image_transport tutorial

Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored and mjcarroll committed Apr 3, 2020
1 parent 6f57c7f commit b9258eb
Show file tree
Hide file tree
Showing 10 changed files with 16 additions and 15 deletions.
8 changes: 2 additions & 6 deletions camera_calibration_parsers/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,14 +1,10 @@
cmake_minimum_required(VERSION 2.8)
cmake_minimum_required(VERSION 3.0.2)
project(camera_calibration_parsers)

find_package(catkin REQUIRED sensor_msgs rosconsole roscpp roscpp_serialization)

find_package(PythonLibs REQUIRED)
if(PYTHONLIBS_VERSION_STRING VERSION_LESS 3)
find_package(Boost REQUIRED COMPONENTS filesystem python)
else()
find_package(Boost REQUIRED COMPONENTS filesystem python3)
endif()
find_package(Boost REQUIRED COMPONENTS filesystem python)
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${PYTHON_INCLUDE_DIRS})

catkin_python_setup()
Expand Down
3 changes: 2 additions & 1 deletion camera_calibration_parsers/setup.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

from setuptools import setup

# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['camera_calibration_parsers'],
Expand Down
6 changes: 5 additions & 1 deletion camera_calibration_parsers/src/parse_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,11 @@ boost::python::tuple readCalibrationWrapper(const std::string& file_name)
sensor_msgs::CameraInfo camera_info;
bool result = readCalibration(file_name, camera_name, camera_info);
std::string cam_info = to_python(camera_info);
return boost::python::make_tuple(result, camera_name, cam_info);
PyObject * cam_info_py = PyBytes_FromStringAndSize(cam_info.c_str(), cam_info.size());
return boost::python::make_tuple(
result,
camera_name,
boost::python::object(boost::python::handle<>(cam_info_py)));
}

BOOST_PYTHON_MODULE(camera_calibration_parsers_wrapper)
Expand Down
2 changes: 1 addition & 1 deletion camera_calibration_parsers/test/parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ def test_ini(self):
for dir in [ '', './']:
p = subprocess.Popen('rosrun camera_calibration_parsers convert $(rospack find camera_calibration_parsers)/test/%s %s%s' % (files[0], dir, files[1]), shell=True, stderr=subprocess.PIPE)
out, err = p.communicate()
self.assertEqual(err, '')
self.assertEqual(err, b'')

def test_readCalibration(self):
script_dir = os.path.dirname(os.path.realpath(__file__))
Expand Down
2 changes: 1 addition & 1 deletion camera_info_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8)
cmake_minimum_required(VERSION 3.0.2)
project(camera_info_manager)

find_package(catkin REQUIRED COMPONENTS camera_calibration_parsers image_transport roscpp roslib sensor_msgs)
Expand Down
2 changes: 1 addition & 1 deletion image_common/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.2)
project(image_common)
find_package(catkin REQUIRED)
catkin_metapackage()
2 changes: 1 addition & 1 deletion image_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.2)
project(image_transport)

find_package(catkin REQUIRED
Expand Down
2 changes: 1 addition & 1 deletion image_transport/tutorial/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8)
cmake_minimum_required(VERSION 3.0.2)
project(image_transport_tutorial)

find_package(catkin REQUIRED COMPONENTS cv_bridge image_transport message_generation sensor_msgs)
Expand Down
2 changes: 1 addition & 1 deletion image_transport/tutorial/src/my_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ int main(int argc, char** argv)
image_transport::ImageTransport it(nh);
image_transport::Publisher pub = it.advertise("camera/image", 1);

cv::Mat image = cv::imread(argv[1], CV_LOAD_IMAGE_COLOR);
cv::Mat image = cv::imread(argv[1], cv::IMREAD_COLOR);
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();

ros::Rate loop_rate(5);
Expand Down
2 changes: 1 addition & 1 deletion polled_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8)
cmake_minimum_required(VERSION 3.0.2)
project(polled_camera)

# generate the server
Expand Down

0 comments on commit b9258eb

Please sign in to comment.