From 0368d2ae801feaed1c617cc3a79a78923e9a2fc7 Mon Sep 17 00:00:00 2001 From: "CW01\\uig08771" Date: Sat, 6 Jul 2024 15:40:44 +0800 Subject: [PATCH 1/2] Use IMAGE_TRANSPORT_PUBLIC at class level for windows gcc build --- .../image_transport/camera_publisher.hpp | 17 +---------------- .../image_transport/camera_subscriber.hpp | 13 +------------ .../include/image_transport/image_transport.hpp | 15 +-------------- .../include/image_transport/publisher.hpp | 14 +------------- .../single_subscriber_publisher.hpp | 8 +------- .../include/image_transport/subscriber.hpp | 13 ++----------- .../image_transport/subscriber_filter.hpp | 11 +---------- .../include/image_transport/transport_hints.hpp | 4 +--- 8 files changed, 9 insertions(+), 86 deletions(-) diff --git a/image_transport/include/image_transport/camera_publisher.hpp b/image_transport/include/image_transport/camera_publisher.hpp index ad80328c..60f5739d 100644 --- a/image_transport/include/image_transport/camera_publisher.hpp +++ b/image_transport/include/image_transport/camera_publisher.hpp @@ -61,13 +61,11 @@ 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_PUBLIC CameraPublisher { public: - IMAGE_TRANSPORT_PUBLIC CameraPublisher() = default; - IMAGE_TRANSPORT_PUBLIC CameraPublisher( rclcpp::Node * node, const std::string & base_topic, @@ -80,25 +78,21 @@ class CameraPublisher * * Returns max(image topic subscribers, info topic subscribers). */ - IMAGE_TRANSPORT_PUBLIC size_t getNumSubscribers() const; /*! * \brief Returns the base (image) topic of this CameraPublisher. */ - IMAGE_TRANSPORT_PUBLIC std::string getTopic() const; /** * \brief Returns the camera info topic of this CameraPublisher. */ - IMAGE_TRANSPORT_PUBLIC std::string getInfoTopic() const; /*! * \brief Publish an (image, info) pair on the topics associated with this CameraPublisher. */ - IMAGE_TRANSPORT_PUBLIC void publish( const sensor_msgs::msg::Image & image, const sensor_msgs::msg::CameraInfo & info) const; @@ -106,7 +100,6 @@ class CameraPublisher /*! * \brief Publish an (image, info) pair on the topics associated with this CameraPublisher. */ - IMAGE_TRANSPORT_PUBLIC void publish( const sensor_msgs::msg::Image::ConstSharedPtr & image, const sensor_msgs::msg::CameraInfo::ConstSharedPtr & info) const; @@ -114,7 +107,6 @@ class CameraPublisher /*! * \brief Publish an (image, info) pair on the topics associated with this CameraPublisher. */ - IMAGE_TRANSPORT_PUBLIC void publish( sensor_msgs::msg::Image::UniquePtr image, sensor_msgs::msg::CameraInfo::UniquePtr info) const; @@ -126,7 +118,6 @@ class CameraPublisher * Convenience version, which sets the timestamps of both image and info to stamp before * publishing. */ - IMAGE_TRANSPORT_PUBLIC void publish( sensor_msgs::msg::Image & image, sensor_msgs::msg::CameraInfo & info, rclcpp::Time stamp) const; @@ -138,7 +129,6 @@ class CameraPublisher * Convenience version, which sets the timestamps of both image and info to stamp before * publishing. */ - IMAGE_TRANSPORT_PUBLIC void publish( sensor_msgs::msg::Image::UniquePtr image, sensor_msgs::msg::CameraInfo::UniquePtr info, @@ -147,19 +137,14 @@ class CameraPublisher /*! * \brief Shutdown the advertisements associated with this Publisher. */ - IMAGE_TRANSPORT_PUBLIC void shutdown(); - IMAGE_TRANSPORT_PUBLIC operator void *() const; - IMAGE_TRANSPORT_PUBLIC bool operator<(const CameraPublisher & rhs) const {return impl_ < rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator!=(const CameraPublisher & rhs) const {return impl_ != rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator==(const CameraPublisher & rhs) const {return impl_ == rhs.impl_;} private: diff --git a/image_transport/include/image_transport/camera_subscriber.hpp b/image_transport/include/image_transport/camera_subscriber.hpp index 5157111d..a7eafa02 100644 --- a/image_transport/include/image_transport/camera_subscriber.hpp +++ b/image_transport/include/image_transport/camera_subscriber.hpp @@ -60,16 +60,14 @@ void callback(const sensor_msgs::msg::Image::ConstSharedPtr&, const sensor_msgs: * 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_PUBLIC CameraSubscriber { public: typedef std::function Callback; - IMAGE_TRANSPORT_PUBLIC CameraSubscriber() = default; - IMAGE_TRANSPORT_PUBLIC CameraSubscriber( rclcpp::Node * node, const std::string & base_topic, @@ -80,43 +78,34 @@ class CameraSubscriber /** * \brief Get the base topic (on which the raw image is published). */ - IMAGE_TRANSPORT_PUBLIC std::string getTopic() const; /** * \brief Get the camera info topic. */ - IMAGE_TRANSPORT_PUBLIC std::string getInfoTopic() const; /** * \brief Returns the number of publishers this subscriber is connected to. */ - IMAGE_TRANSPORT_PUBLIC size_t getNumPublishers() const; /** * \brief Returns the name of the transport being used. */ - IMAGE_TRANSPORT_PUBLIC std::string getTransport() const; /** * \brief Unsubscribe the callback associated with this CameraSubscriber. */ - IMAGE_TRANSPORT_PUBLIC void shutdown(); - IMAGE_TRANSPORT_PUBLIC operator void *() const; - IMAGE_TRANSPORT_PUBLIC bool operator<(const CameraSubscriber & rhs) const {return impl_ < rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator!=(const CameraSubscriber & rhs) const {return impl_ != rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator==(const CameraSubscriber & rhs) const {return impl_ == rhs.impl_;} private: diff --git a/image_transport/include/image_transport/image_transport.hpp b/image_transport/include/image_transport/image_transport.hpp index e430cd92..dd5eb629 100644 --- a/image_transport/include/image_transport/image_transport.hpp +++ b/image_transport/include/image_transport/image_transport.hpp @@ -102,29 +102,25 @@ std::vector getLoadableTransports(); * subscribe() functions for creating advertisements and subscriptions of image topics. */ -class ImageTransport +class IMAGE_TRANSPORT_PUBLIC ImageTransport { public: using VoidPtr = std::shared_ptr; using ImageConstPtr = sensor_msgs::msg::Image::ConstSharedPtr; using CameraInfoConstPtr = sensor_msgs::msg::CameraInfo::ConstSharedPtr; - IMAGE_TRANSPORT_PUBLIC explicit ImageTransport(rclcpp::Node::SharedPtr node); - IMAGE_TRANSPORT_PUBLIC ~ImageTransport(); /*! * \brief Advertise an image topic, simple version. */ - IMAGE_TRANSPORT_PUBLIC Publisher advertise(const std::string & base_topic, uint32_t queue_size, bool latch = false); /*! * \brief Advertise an image topic, simple version. */ - IMAGE_TRANSPORT_PUBLIC Publisher advertise( const std::string & base_topic, rmw_qos_profile_t custom_qos, bool latch = false); @@ -142,7 +138,6 @@ class ImageTransport /** * \brief Subscribe to an image topic, version for arbitrary std::function object. */ - IMAGE_TRANSPORT_PUBLIC Subscriber subscribe( const std::string & base_topic, uint32_t queue_size, const Subscriber::Callback & callback, @@ -153,7 +148,6 @@ class ImageTransport /** * \brief Subscribe to an image topic, version for bare function. */ - IMAGE_TRANSPORT_PUBLIC Subscriber subscribe( const std::string & base_topic, uint32_t queue_size, void (* fp)(const ImageConstPtr &), @@ -200,7 +194,6 @@ class ImageTransport /** * \brief Subscribe to an image topic, version for arbitrary std::function object and QoS. */ - IMAGE_TRANSPORT_PUBLIC Subscriber subscribe( const std::string & base_topic, rmw_qos_profile_t custom_qos, const Subscriber::Callback & callback, @@ -211,7 +204,6 @@ class ImageTransport /** * \brief Subscribe to an image topic, version for bare function. */ - IMAGE_TRANSPORT_PUBLIC Subscriber subscribe( const std::string & base_topic, rmw_qos_profile_t custom_qos, void (* fp)(const ImageConstPtr &), @@ -258,7 +250,6 @@ class ImageTransport /*! * \brief Advertise a synchronized camera raw image + info topic pair, simple version. */ - IMAGE_TRANSPORT_PUBLIC CameraPublisher advertiseCamera( const std::string & base_topic, uint32_t queue_size, bool latch = false); @@ -283,7 +274,6 @@ class ImageTransport * This version assumes the standard topic naming scheme, where the info topic is * named "camera_info" in the same namespace as the base image topic. */ - IMAGE_TRANSPORT_PUBLIC CameraSubscriber subscribeCamera( const std::string & base_topic, uint32_t queue_size, const CameraSubscriber::Callback & callback, @@ -293,7 +283,6 @@ class ImageTransport /** * \brief Subscribe to a synchronized image & camera info topic pair, version for bare function. */ - IMAGE_TRANSPORT_PUBLIC CameraSubscriber subscribeCamera( const std::string & base_topic, uint32_t queue_size, void (* fp)( @@ -348,13 +337,11 @@ class ImageTransport * \brief Returns the names of all transports declared in the system. Declared * transports are not necessarily built or loadable. */ - IMAGE_TRANSPORT_PUBLIC std::vector getDeclaredTransports() const; /** * \brief Returns the names of all transports that are loadable in the system. */ - IMAGE_TRANSPORT_PUBLIC std::vector getLoadableTransports() const; private: diff --git a/image_transport/include/image_transport/publisher.hpp b/image_transport/include/image_transport/publisher.hpp index 4f529121..f012c170 100644 --- a/image_transport/include/image_transport/publisher.hpp +++ b/image_transport/include/image_transport/publisher.hpp @@ -62,13 +62,11 @@ 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_PUBLIC Publisher { public: - IMAGE_TRANSPORT_PUBLIC Publisher() = default; - IMAGE_TRANSPORT_PUBLIC Publisher( rclcpp::Node * nh, const std::string & base_topic, @@ -82,49 +80,39 @@ class Publisher * * Returns the total number of subscribers to all advertised topics. */ - IMAGE_TRANSPORT_PUBLIC size_t getNumSubscribers() const; /*! * \brief Returns the base topic of this Publisher. */ - IMAGE_TRANSPORT_PUBLIC std::string getTopic() const; /*! * \brief Publish an image on the topics associated with this Publisher. */ - IMAGE_TRANSPORT_PUBLIC void publish(const sensor_msgs::msg::Image & message) const; /*! * \brief Publish an image on the topics associated with this Publisher. */ - IMAGE_TRANSPORT_PUBLIC void publish(const sensor_msgs::msg::Image::ConstSharedPtr & message) const; /*! * \brief Publish an image on the topics associated with this Publisher. */ - IMAGE_TRANSPORT_PUBLIC void publish(sensor_msgs::msg::Image::UniquePtr message) const; /*! * \brief Shutdown the advertisements associated with this Publisher. */ - IMAGE_TRANSPORT_PUBLIC void shutdown(); - IMAGE_TRANSPORT_PUBLIC operator void *() const; - IMAGE_TRANSPORT_PUBLIC bool operator<(const Publisher & rhs) const {return impl_ < rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator!=(const Publisher & rhs) const {return impl_ != rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator==(const Publisher & rhs) const {return impl_ == rhs.impl_;} private: diff --git a/image_transport/include/image_transport/single_subscriber_publisher.hpp b/image_transport/include/image_transport/single_subscriber_publisher.hpp index e6347db8..f7830447 100644 --- a/image_transport/include/image_transport/single_subscriber_publisher.hpp +++ b/image_transport/include/image_transport/single_subscriber_publisher.hpp @@ -44,7 +44,7 @@ namespace image_transport * \brief Allows publication of an image to a single subscriber. Only available inside * subscriber connection callbacks. */ -class SingleSubscriberPublisher +class IMAGE_TRANSPORT_PUBLIC SingleSubscriberPublisher { private: SingleSubscriberPublisher(const SingleSubscriberPublisher &) = delete; @@ -54,25 +54,19 @@ class SingleSubscriberPublisher typedef std::function GetNumSubscribersFn; typedef std::function PublishFn; - IMAGE_TRANSPORT_PUBLIC SingleSubscriberPublisher( const std::string & caller_id, const std::string & topic, const GetNumSubscribersFn & num_subscribers_fn, const PublishFn & publish_fn); - IMAGE_TRANSPORT_PUBLIC std::string getSubscriberName() const; - IMAGE_TRANSPORT_PUBLIC std::string getTopic() const; - IMAGE_TRANSPORT_PUBLIC size_t getNumSubscribers() const; - IMAGE_TRANSPORT_PUBLIC void publish(const sensor_msgs::msg::Image & message) const; - IMAGE_TRANSPORT_PUBLIC void publish(const sensor_msgs::msg::Image::ConstSharedPtr & message) const; private: diff --git a/image_transport/include/image_transport/subscriber.hpp b/image_transport/include/image_transport/subscriber.hpp index f0b87245..0dbd5b9f 100644 --- a/image_transport/include/image_transport/subscriber.hpp +++ b/image_transport/include/image_transport/subscriber.hpp @@ -58,15 +58,14 @@ 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_PUBLIC Subscriber { public: typedef std::function Callback; - IMAGE_TRANSPORT_PUBLIC + Subscriber() = default; - IMAGE_TRANSPORT_PUBLIC Subscriber( rclcpp::Node * node, const std::string & base_topic, @@ -82,34 +81,26 @@ class Subscriber * The Subscriber may actually be subscribed to some transport-specific topic that * differs from the base topic. */ - IMAGE_TRANSPORT_PUBLIC std::string getTopic() const; /** * \brief Returns the number of publishers this subscriber is connected to. */ - IMAGE_TRANSPORT_PUBLIC size_t getNumPublishers() const; /** * \brief Returns the name of the transport being used. */ - IMAGE_TRANSPORT_PUBLIC std::string getTransport() const; /** * \brief Unsubscribe the callback associated with this Subscriber. */ - IMAGE_TRANSPORT_PUBLIC void shutdown(); - IMAGE_TRANSPORT_PUBLIC operator void *() const; - IMAGE_TRANSPORT_PUBLIC bool operator<(const Subscriber & rhs) const {return impl_ < rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator!=(const Subscriber & rhs) const {return impl_ != rhs.impl_;} - IMAGE_TRANSPORT_PUBLIC bool operator==(const Subscriber & rhs) const {return impl_ == rhs.impl_;} private: diff --git a/image_transport/include/image_transport/subscriber_filter.hpp b/image_transport/include/image_transport/subscriber_filter.hpp index 37b216ed..cec897e3 100644 --- a/image_transport/include/image_transport/subscriber_filter.hpp +++ b/image_transport/include/image_transport/subscriber_filter.hpp @@ -62,7 +62,7 @@ void callback(const std::shared_ptr&); \endverbatim */ -class SubscriberFilter : public message_filters::SimpleFilter +class IMAGE_TRANSPORT_PUBLIC SubscriberFilter : public message_filters::SimpleFilter { public: /** @@ -75,7 +75,6 @@ class SubscriberFilter : public message_filters::SimpleFilterget_parameter_or(parameter_name, transport_, default_transport); } - IMAGE_TRANSPORT_PUBLIC const std::string & getTransport() const { return transport_; From 29d37763515be692122b9ad79960a06fd5e0cf98 Mon Sep 17 00:00:00 2001 From: "CW01\\uig08771" Date: Sat, 6 Jul 2024 23:17:09 +0800 Subject: [PATCH 2/2] fix cpplint whitespace and line length --- image_transport/include/image_transport/subscriber.hpp | 1 - image_transport/include/image_transport/subscriber_filter.hpp | 3 ++- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/image_transport/include/image_transport/subscriber.hpp b/image_transport/include/image_transport/subscriber.hpp index 0dbd5b9f..7bc24668 100644 --- a/image_transport/include/image_transport/subscriber.hpp +++ b/image_transport/include/image_transport/subscriber.hpp @@ -63,7 +63,6 @@ class IMAGE_TRANSPORT_PUBLIC Subscriber public: typedef std::function Callback; - Subscriber() = default; Subscriber( diff --git a/image_transport/include/image_transport/subscriber_filter.hpp b/image_transport/include/image_transport/subscriber_filter.hpp index cec897e3..c5afc065 100644 --- a/image_transport/include/image_transport/subscriber_filter.hpp +++ b/image_transport/include/image_transport/subscriber_filter.hpp @@ -62,7 +62,8 @@ void callback(const std::shared_ptr&); \endverbatim */ -class IMAGE_TRANSPORT_PUBLIC SubscriberFilter : public message_filters::SimpleFilter +class IMAGE_TRANSPORT_PUBLIC SubscriberFilter + : public message_filters::SimpleFilter { public: /**