39 #include <boost/make_shared.hpp> 
   40 #include <boost/foreach.hpp> 
   41 #include <boost/algorithm/string/erase.hpp> 
   45 struct ImageTransport::Impl
 
   64 ImageTransport::~ImageTransport()
 
   68 Publisher ImageTransport::advertise(
const std::string& base_topic, uint32_t queue_size, 
bool latch)
 
   74 Publisher ImageTransport::advertise(
const std::string& base_topic, uint32_t queue_size,
 
   79   return Publisher(impl_->nh_, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch, impl_->pub_loader_);
 
   82 Subscriber ImageTransport::subscribe(
const std::string& base_topic, uint32_t queue_size,
 
   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_);
 
   89 CameraPublisher ImageTransport::advertiseCamera(
const std::string& base_topic, uint32_t queue_size, 
bool latch)
 
   91   return advertiseCamera(base_topic, queue_size,
 
   97 CameraPublisher ImageTransport::advertiseCamera(
const std::string& base_topic, uint32_t queue_size,
 
  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);
 
  108 CameraSubscriber ImageTransport::subscribeCamera(
const std::string& base_topic, uint32_t queue_size,
 
  113   return CameraSubscriber(*
this, impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints);
 
  116 std::vector<std::string> ImageTransport::getDeclaredTransports()
 const 
  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");
 
  126 std::vector<std::string> ImageTransport::getLoadableTransports()
 const 
  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;