Skip to content

Commit

Permalink
Restore comments and naming.
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll committed Aug 3, 2018
1 parent 17723b3 commit 08c7945
Show file tree
Hide file tree
Showing 2 changed files with 59 additions and 12 deletions.
59 changes: 55 additions & 4 deletions image_transport/include/image_transport/image_transport.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,21 +74,37 @@ CameraSubscriber create_camera_subscription(
std::vector<std::string> getDeclaredTransports();
std::vector<std::string> getLoadableTransports();

/**
* \brief Advertise and subscribe to image topics.
*
* ImageTransport is analogous to ros::NodeHandle in that it contains advertise() and
* subscribe() functions for creating advertisements and subscriptions of image topics.
*/
class ImageTransport
{
public:
ImageTransport(rclcpp::Node::SharedPtr node);
explicit ImageTransport(rclcpp::Node::SharedPtr node);

~ImageTransport();

/*!
* \brief Advertise an image topic, simple version.
*/
Publisher advertise(
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

/**
* \brief Subscribe to an image topic, version for arbitrary std::function object.
*/
Subscriber subscribe(
const std::string & base_topic,
const Subscriber::Callback& callback,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

/**
* \brief Subscribe to an image topic, version for bare function.
*/
Subscriber subscribe(
const std::string & base_topic,
void (*fp)(const sensor_msgs::msg::Image::ConstSharedPtr&),
Expand All @@ -97,6 +113,9 @@ class ImageTransport
return subscribe(base_topic, Subscriber::Callback(fp), custom_qos);
}

/**
* \brief Subscribe to an image topic, version for class member function with bare pointer.
*/
template<class T>
Subscriber subscribe(
const std::string & base_topic,
Expand All @@ -107,6 +126,9 @@ class ImageTransport
return subscribe(base_topic, std::bind(fp, obj, std::placeholders::_1), custom_qos);
}

/**
* \brief Subscribe to an image topic, version for class member function with shared_ptr.
*/
template<class T>
Subscriber subscribe(
const std::string & base_topic,
Expand All @@ -117,24 +139,41 @@ class ImageTransport
return subscribe(base_topic, std::bind(fp, obj, std::placeholders::_1), custom_qos);
}

CameraPublisher advertise_camera(
/*!
* \brief Advertise a synchronized camera raw image + info topic pair, simple version.
*/
CameraPublisher advertiseCamera(
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

CameraSubscriber subscribe_camera(
/**
* \brief Subscribe to a synchronized image & camera info topic pair, version for arbitrary
* std::function object.
*
* 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.
*/
CameraSubscriber subscribeCamera(
const std::string & base_topic,
const CameraSubscriber::Callback& callback,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

/**
* \brief Subscribe to a synchronized image & camera info topic pair, version for bare function.
*/
CameraSubscriber subscribe_camera(
const std::string & base_topic,
void (*fp)(const sensor_msgs::msg::Image::ConstSharedPtr&,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr&),
rmw_qos_profile_t custom_qos = rmw_qos_profile_default)
{
return subscribe_camera(base_topic, CameraSubscriber::Callback(fp), custom_qos);
return subscribeCamera(base_topic, CameraSubscriber::Callback(fp), custom_qos);
}

/**
* \brief Subscribe to a synchronized image & camera info topic pair, version for class member
* function with bare pointer.
*/
template<class T>
CameraSubscriber subscribe_camera(
const std::string & base_topic,
Expand All @@ -146,6 +185,10 @@ class ImageTransport
return subscribe_camera(base_topic, std::bind(fp, obj, std::placeholders::_1), custom_qos);
}

/**
* \brief Subscribe to a synchronized image & camera info topic pair, version for class member
* function with shared_ptr.
*/
template<class T>
CameraSubscriber subscribe_camera(
const std::string & base_topic,
Expand All @@ -157,7 +200,15 @@ class ImageTransport
return subscribe_camera(base_topic, std::bind(fp, obj, std::placeholders::_1), custom_qos);
}

/**
* \brief Returns the names of all transports declared in the system. Declared
* transports are not necessarily built or loadable.
*/
std::vector<std::string> getDeclaredTransports() const;

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

private:
Expand Down
12 changes: 4 additions & 8 deletions image_transport/src/image_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,6 @@
#include "image_transport/subscriber_plugin.h"
#include "image_transport/loader_fwds.h"

static constexpr const char* kPluginClass = "image_transport";
static constexpr const char* kSubBase = "image_transport::SubscriberPlugin";
static constexpr const char* kPubBase = "image_transport::PublisherPlugin";

namespace image_transport
{

Expand All @@ -54,8 +50,8 @@ struct Impl {
SubLoaderPtr sub_loader_;

Impl():
pub_loader_(std::make_shared<PubLoader>(kPluginClass, kPubBase)),
sub_loader_(std::make_shared<SubLoader>(kPluginClass, kSubBase))
pub_loader_(std::make_shared<PubLoader>("image_tranport", "image_transport::PublisherPlugin")),
sub_loader_(std::make_shared<SubLoader>("image_tranport", "image_transport::SubscriberPlugin"))
{
}
};
Expand Down Expand Up @@ -155,14 +151,14 @@ Subscriber ImageTransport::subscribe(
return create_subscription(impl_->node_, base_topic, callback, custom_qos);
}

CameraPublisher ImageTransport::advertise_camera(
CameraPublisher ImageTransport::advertiseCamera(
const std::string & base_topic,
rmw_qos_profile_t custom_qos)
{
return create_camera_publisher(impl_->node_, base_topic, custom_qos);
}

CameraSubscriber ImageTransport::subscribe_camera(
CameraSubscriber ImageTransport::subscribeCamera(
const std::string & base_topic,
const CameraSubscriber::Callback& callback,
rmw_qos_profile_t custom_qos)
Expand Down

0 comments on commit 08c7945

Please sign in to comment.