39 #include <boost/make_shared.hpp> 40 #include <boost/foreach.hpp> 41 #include <boost/algorithm/string/erase.hpp> 53 pub_loader_(
boost::make_shared<
PubLoader>(
"image_transport",
"image_transport::PublisherPlugin") ),
54 sub_loader_(
boost::make_shared<
SubLoader>(
"image_transport",
"image_transport::SubscriberPlugin") )
79 return Publisher(
impl_->nh_, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch,
impl_->pub_loader_);
83 const boost::function<
void(
const sensor_msgs::ImageConstPtr&)>& callback,
86 return Subscriber(
impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints,
impl_->sub_loader_);
104 return CameraPublisher(*
this,
impl_->nh_, base_topic, queue_size, image_connect_cb, image_disconnect_cb,
105 info_connect_cb, info_disconnect_cb, tracked_object, latch);
113 return CameraSubscriber(*
this,
impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints);
118 std::vector<std::string> transports =
impl_->sub_loader_->getDeclaredClasses();
120 BOOST_FOREACH(std::string& transport, transports) {
121 transport = boost::erase_last_copy(transport,
"_sub");
128 std::vector<std::string> loadableTransports;
130 BOOST_FOREACH(
const std::string& transportPlugin,
impl_->sub_loader_->getDeclaredClasses() )
138 loadableTransports.push_back(boost::erase_last_copy(transportPlugin,
"_sub"));
144 return loadableTransports;
Manages advertisements of multiple transport options on an Image topic.
std::vector< std::string > getLoadableTransports() const
Returns the names of all transports that are loadable in the system.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ImageTransport(const ros::NodeHandle &nh)
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function obj...
Impl(const ros::NodeHandle &nh)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
Manages advertisements for publishing camera images.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Manages a subscription callback on a specific topic that can be interpreted as an Image topic...
Manages a subscription callback on synchronized Image and CameraInfo topics.
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise a synchronized camera raw image + info topic pair, simple version.
std::vector< std::string > getDeclaredTransports() const
Returns the names of all transports declared in the system. Declared transports are not necessarily b...
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.