Skip to content

Commit

Permalink
Merge branch 'hydro-devel' into fisheye
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidTorresOcana committed Aug 2, 2020
2 parents c3f4c1d + 6f57c7f commit 00d1fee
Show file tree
Hide file tree
Showing 24 changed files with 111 additions and 19 deletions.
3 changes: 3 additions & 0 deletions camera_calibration_parsers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package camera_calibration_parsers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

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

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

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
4 changes: 3 additions & 1 deletion camera_info_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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.11.14</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
3 changes: 3 additions & 0 deletions image_common/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package image_common
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

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

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

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

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
7 changes: 5 additions & 2 deletions image_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
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.11.14</version>
<description>

image_transport should always be used to subscribe to and publish images. It provides transparent
Expand Down
6 changes: 6 additions & 0 deletions polled_camera/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package polled_camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

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)
--------------------

Expand Down
4 changes: 3 additions & 1 deletion polled_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,9 @@ add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EX
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}
)
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
Expand Down
16 changes: 15 additions & 1 deletion polled_camera/include/polled_camera/publication_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,20 @@
#include <sensor_msgs/CameraInfo.h>
#include "polled_camera/GetPolledImage.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 polled_camera_EXPORTS // we are building a shared lib/dll
#define POLLED_CAMERA_DECL ROS_HELPER_EXPORT
#else // we are using shared lib/dll
#define POLLED_CAMERA_DECL ROS_HELPER_IMPORT
#endif
#else // ros is being built around static libraries
#define POLLED_CAMERA_DECL
#endif

namespace polled_camera {

/**
Expand All @@ -63,7 +77,7 @@ void callback(polled_camera::GetPolledImage::Request& req,
}
\endcode
*/
class PublicationServer
class POLLED_CAMERA_DECL PublicationServer
{
public:
typedef boost::function<void (polled_camera::GetPolledImage::Request&,
Expand Down
2 changes: 1 addition & 1 deletion polled_camera/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>polled_camera</name>
<version>1.11.13</version>
<version>1.11.14</version>
<description>

polled_camera contains a service and C++ helper classes for implementing a polled
Expand Down

0 comments on commit 00d1fee

Please sign in to comment.