Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/noetic-devel' into fisheye
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidTorresOcana committed Aug 23, 2020
2 parents c3f4c1d + 3eed8b5 commit 534c419
Show file tree
Hide file tree
Showing 31 changed files with 168 additions and 34 deletions.
16 changes: 16 additions & 0 deletions camera_calibration_parsers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,22 @@
Changelog for package camera_calibration_parsers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.12.0 (2020-04-03)
-------------------
* Noetic release image_common (`#155 <https://github.com/ros-perception/image_common/issues/155>`_)
* 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]>
* Contributors: Alejandro Hernández Cordero

1.11.14 (2020-04-03)
--------------------

1.11.13 (2017-11-05)
--------------------
* Use Boost_LIBRARIES instead of Boost_PYTHON_LIBRARY
Expand Down
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
2 changes: 1 addition & 1 deletion camera_calibration_parsers/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>camera_calibration_parsers</name>
<version>1.11.13</version>
<version>1.12.0</version>
<description>
camera_calibration_parsers contains routines for reading and writing camera calibration parameters.
</description>
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
20 changes: 20 additions & 0 deletions camera_info_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,26 @@
Changelog for package camera_info_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.12.0 (2020-04-03)
-------------------
* Noetic release image_common (`#155 <https://github.com/ros-perception/image_common/issues/155>`_)
* 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]>
* Contributors: Alejandro Hernández Cordero

1.11.14 (2020-04-03)
--------------------
* export runtime binaries correctly on Windows (`#116 <https://github.com/ros-perception/image_common/issues/116>`_)
* add indentation, and use _WIN32 instead of WIN32 (`#117 <https://github.com/ros-perception/image_common/issues/117>`_)
* add DLL import/export macro (`#118 <https://github.com/ros-perception/image_common/issues/118>`_)
* Contributors: James Xu

1.11.13 (2017-11-05)
--------------------
* Fix the find_package(catkin) redundancy
Expand Down
6 changes: 4 additions & 2 deletions 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 All @@ -18,7 +18,9 @@ add_library(${PROJECT_NAME} src/camera_info_manager.cpp)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})

install(TARGETS ${PROJECT_NAME}
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
COMPONENT main
)
install(DIRECTORY include/${PROJECT_NAME}/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,20 @@
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/SetCameraInfo.h>

#include <ros/macros.h>

// Import/export for windows dll's and visibility for gcc shared libraries.

#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
#ifdef camera_info_manager_EXPORTS // we are building a shared lib/dll
#define CAMERA_INFO_MANAGER_DECL ROS_HELPER_EXPORT
#else // we are using shared lib/dll
#define CAMERA_INFO_MANAGER_DECL ROS_HELPER_IMPORT
#endif
#else // ros is being built around static libraries
#define CAMERA_INFO_MANAGER_DECL
#endif

/** @file
@brief CameraInfo Manager interface
Expand Down Expand Up @@ -171,7 +185,7 @@ namespace camera_info_manager
*/

class CameraInfoManager
class CAMERA_INFO_MANAGER_DECL CameraInfoManager
{
public:

Expand Down
2 changes: 1 addition & 1 deletion camera_info_manager/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>camera_info_manager</name>
<version>1.11.13</version>
<version>1.12.0</version>
<description>

This package provides a C++ interface for camera calibration
Expand Down
9 changes: 8 additions & 1 deletion camera_info_manager/src/camera_info_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,14 @@
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <unistd.h>
#ifdef _WIN32
#ifndef S_ISDIR
#define S_ISDIR(mode) (((mode) & S_IFMT) == S_IFDIR)
#endif
#else
#include <unistd.h>
#endif

#include <ros/ros.h>
#include <ros/package.h>
#include <boost/algorithm/string.hpp>
Expand Down
8 changes: 8 additions & 0 deletions image_common/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package image_common
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.12.0 (2020-04-03)
-------------------
* Noetic release image_common (`#155 <https://github.com/ros-perception/image_common/issues/155>`_)
* Contributors: Alejandro Hernández Cordero

1.11.14 (2020-04-03)
--------------------

1.11.13 (2017-11-05)
--------------------

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_common/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>image_common</name>
<version>1.11.13</version>
<version>1.12.0</version>
<description>Common code for working with images in ROS.</description>
<author>Patrick Mihelich</author>
<author>James Bowman</author>
Expand Down
11 changes: 11 additions & 0 deletions image_transport/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,17 @@
Changelog for package image_transport
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.12.0 (2020-04-03)
-------------------
* Noetic release image_common (`#155 <https://github.com/ros-perception/image_common/issues/155>`_)
* Contributors: Alejandro Hernández Cordero

1.11.14 (2020-04-03)
--------------------
* export runtime binaries correctly on Windows (`#116 <https://github.com/ros-perception/image_common/issues/116>`_)
* add DLL import/export macro (`#118 <https://github.com/ros-perception/image_common/issues/118>`_)
* Contributors: James Xu

1.11.13 (2017-11-05)
--------------------
* Disable image publisher plugins by name (`#60 <https://github.com/ros-perception/image_common/issues/60>`_)
Expand Down
9 changes: 6 additions & 3 deletions 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 Expand Up @@ -37,12 +37,15 @@ target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
)

# Build libimage_transport_plugins
# Build libimage_transport_plugins
add_library(${PROJECT_NAME}_plugins src/manifest.cpp src/raw_publisher.cpp)
target_link_libraries(${PROJECT_NAME}_plugins ${PROJECT_NAME})

# Install plugin DLL to ${CATKIN_PACKAGE_LIB_DESTINATION} according to the path in default_plugins.xml
install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_plugins
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
COMPONENT main
)
install(DIRECTORY include/${PROJECT_NAME}/
Expand Down
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/camera_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#define IMAGE_TRANSPORT_CAMERA_COMMON_H

#include <string>
#include "exports.h"

namespace image_transport {

Expand All @@ -45,7 +46,7 @@ namespace image_transport {
* \note This function assumes that the name is completely resolved. If the \c
* base_topic is remapped the resulting camera info topic will be incorrect.
*/
std::string getCameraInfoTopic(const std::string& base_topic);
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string& base_topic);

} //namespace image_transport

Expand Down
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/camera_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
#include "image_transport/single_subscriber_publisher.h"
#include "exports.h"

namespace image_transport {

Expand All @@ -59,7 +60,7 @@ class ImageTransport;
* associated with that handle will stop being called. Once all CameraPublisher for a
* given base topic go out of scope the topic (and all subtopics) will be unadvertised.
*/
class CameraPublisher
class IMAGE_TRANSPORT_DECL CameraPublisher
{
public:
CameraPublisher() {}
Expand Down
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/camera_subscriber.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Image.h>
#include "image_transport/transport_hints.h"
#include "exports.h"

namespace image_transport {

Expand All @@ -59,7 +60,7 @@ void callback(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoCo
* associated with that handle will stop being called. Once all CameraSubscriber for a given
* topic go out of scope the topic will be unsubscribed.
*/
class CameraSubscriber
class IMAGE_TRANSPORT_DECL CameraSubscriber
{
public:
typedef boost::function<void(const sensor_msgs::ImageConstPtr&,
Expand Down
18 changes: 18 additions & 0 deletions image_transport/include/image_transport/exports.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#ifndef IMAGE_TRANSPORT_EXPORTS_H
#define IMAGE_TRANSPORT_EXPORTS_H

#include <ros/macros.h>

// Import/export for windows dll's and visibility for gcc shared libraries.

#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
#ifdef image_transport_EXPORTS // we are building a shared lib/dll
#define IMAGE_TRANSPORT_DECL ROS_HELPER_EXPORT
#else // we are using shared lib/dll
#define IMAGE_TRANSPORT_DECL ROS_HELPER_IMPORT
#endif
#else // ros is being built around static libraries
#define IMAGE_TRANSPORT_DECL
#endif

#endif // IMAGE_TRANSPORT_EXPORTS_H
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/image_transport.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "image_transport/subscriber.h"
#include "image_transport/camera_publisher.h"
#include "image_transport/camera_subscriber.h"
#include "exports.h"

namespace image_transport {

Expand All @@ -48,7 +49,7 @@ namespace image_transport {
* ImageTransport is analogous to ros::NodeHandle in that it contains advertise() and
* subscribe() functions for creating advertisements and subscriptions of image topics.
*/
class ImageTransport
class IMAGE_TRANSPORT_DECL ImageTransport
{
public:
explicit ImageTransport(const ros::NodeHandle& nh);
Expand Down
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include "image_transport/single_subscriber_publisher.h"
#include "image_transport/exception.h"
#include "image_transport/loader_fwds.h"
#include "exports.h"

namespace image_transport {

Expand All @@ -60,7 +61,7 @@ namespace image_transport {
* associated with that handle will stop being called. Once all Publisher for a
* given base topic go out of scope the topic (and all subtopics) will be unadvertised.
*/
class Publisher
class IMAGE_TRANSPORT_DECL Publisher
{
public:
Publisher() {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,15 @@
#include <boost/noncopyable.hpp>
#include <boost/function.hpp>
#include <sensor_msgs/Image.h>
#include "exports.h"

namespace image_transport {

/**
* \brief Allows publication of an image to a single subscriber. Only available inside
* subscriber connection callbacks.
*/
class SingleSubscriberPublisher : boost::noncopyable
class IMAGE_TRANSPORT_DECL SingleSubscriberPublisher : boost::noncopyable
{
public:
typedef boost::function<uint32_t()> GetNumSubscribersFn;
Expand Down
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/subscriber.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include "image_transport/transport_hints.h"
#include "image_transport/exception.h"
#include "image_transport/loader_fwds.h"
#include "exports.h"

namespace image_transport {

Expand All @@ -58,7 +59,7 @@ namespace image_transport {
* associated with that handle will stop being called. Once all Subscriber for a given
* topic go out of scope the topic will be unsubscribed.
*/
class Subscriber
class IMAGE_TRANSPORT_DECL Subscriber
{
public:
Subscriber() {}
Expand Down
2 changes: 1 addition & 1 deletion image_transport/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>image_transport</name>
<version>1.11.13</version>
<version>1.12.0</version>
<description>

image_transport should always be used to subscribe to and publish images. It provides transparent
Expand Down
Loading

0 comments on commit 534c419

Please sign in to comment.