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

Use IMAGE_TRANSPORT_PUBLIC at class level for windows gcc build #316

Open
wants to merge 2 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
17 changes: 1 addition & 16 deletions image_transport/include/image_transport/camera_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -80,41 +78,35 @@ 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;

/*!
* \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;

/*!
* \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;
Expand All @@ -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;
Expand All @@ -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,
Expand All @@ -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:
Expand Down
13 changes: 1 addition & 12 deletions image_transport/include/image_transport/camera_subscriber.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<void (const sensor_msgs::msg::Image::ConstSharedPtr &,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr &)> Callback;

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber() = default;

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber(
rclcpp::Node * node,
const std::string & base_topic,
Expand All @@ -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:
Expand Down
15 changes: 1 addition & 14 deletions image_transport/include/image_transport/image_transport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,29 +102,25 @@ std::vector<std::string> getLoadableTransports();
* subscribe() functions for creating advertisements and subscriptions of image topics.
*/

class ImageTransport
class IMAGE_TRANSPORT_PUBLIC ImageTransport
{
public:
using VoidPtr = std::shared_ptr<void>;
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);
Expand All @@ -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,
Expand All @@ -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 &),
Expand Down Expand Up @@ -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,
Expand All @@ -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 &),
Expand Down Expand Up @@ -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);
Expand All @@ -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,
Expand All @@ -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)(
Expand Down Expand Up @@ -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<std::string> getDeclaredTransports() const;

/**
* \brief Returns the names of all transports that are loadable in the system.
*/
IMAGE_TRANSPORT_PUBLIC
std::vector<std::string> getLoadableTransports() const;

private:
Expand Down
14 changes: 1 addition & 13 deletions image_transport/include/image_transport/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -54,25 +54,19 @@ class SingleSubscriberPublisher
typedef std::function<size_t ()> GetNumSubscribersFn;
typedef std::function<void (const sensor_msgs::msg::Image &)> 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:
Expand Down
Loading