00001 #include "image_transport/image_transport.h"
00002 #include "image_transport/publisher_plugin.h"
00003 #include "image_transport/subscriber_plugin.h"
00004 #include <pluginlib/class_loader.h>
00005 #include <boost/make_shared.hpp>
00006 #include <boost/foreach.hpp>
00007 #include <boost/algorithm/string/erase.hpp>
00008
00009 namespace image_transport {
00010
00011 struct ImageTransport::Impl
00012 {
00013 ros::NodeHandle nh_;
00014 PubLoaderPtr pub_loader_;
00015 SubLoaderPtr sub_loader_;
00016
00017 Impl(const ros::NodeHandle& nh)
00018 : nh_(nh),
00019 pub_loader_( boost::make_shared<PubLoader>("image_transport", "image_transport::PublisherPlugin") ),
00020 sub_loader_( boost::make_shared<SubLoader>("image_transport", "image_transport::SubscriberPlugin") )
00021 {
00022 }
00023 };
00024
00025 ImageTransport::ImageTransport(const ros::NodeHandle& nh)
00026 : impl_(new Impl(nh))
00027 {
00028 }
00029
00030 ImageTransport::~ImageTransport()
00031 {
00032 }
00033
00034 Publisher ImageTransport::advertise(const std::string& base_topic, uint32_t queue_size, bool latch)
00035 {
00036 return advertise(base_topic, queue_size, SubscriberStatusCallback(),
00037 SubscriberStatusCallback(), ros::VoidPtr(), latch);
00038 }
00039
00040 Publisher ImageTransport::advertise(const std::string& base_topic, uint32_t queue_size,
00041 const SubscriberStatusCallback& connect_cb,
00042 const SubscriberStatusCallback& disconnect_cb,
00043 const ros::VoidPtr& tracked_object, bool latch)
00044 {
00045 return Publisher(impl_->nh_, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch, impl_->pub_loader_);
00046 }
00047
00048 Subscriber ImageTransport::subscribe(const std::string& base_topic, uint32_t queue_size,
00049 const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
00050 const ros::VoidPtr& tracked_object, const TransportHints& transport_hints)
00051 {
00052 return Subscriber(impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints, impl_->sub_loader_);
00053 }
00054
00055 CameraPublisher ImageTransport::advertiseCamera(const std::string& base_topic, uint32_t queue_size, bool latch)
00056 {
00057 return advertiseCamera(base_topic, queue_size,
00058 SubscriberStatusCallback(), SubscriberStatusCallback(),
00059 ros::SubscriberStatusCallback(), ros::SubscriberStatusCallback(),
00060 ros::VoidPtr(), latch);
00061 }
00062
00063 CameraPublisher ImageTransport::advertiseCamera(const std::string& base_topic, uint32_t queue_size,
00064 const SubscriberStatusCallback& image_connect_cb,
00065 const SubscriberStatusCallback& image_disconnect_cb,
00066 const ros::SubscriberStatusCallback& info_connect_cb,
00067 const ros::SubscriberStatusCallback& info_disconnect_cb,
00068 const ros::VoidPtr& tracked_object, bool latch)
00069 {
00070 return CameraPublisher(*this, impl_->nh_, base_topic, queue_size, image_connect_cb, image_disconnect_cb,
00071 info_connect_cb, info_disconnect_cb, tracked_object, latch);
00072 }
00073
00074 CameraSubscriber ImageTransport::subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00075 const CameraSubscriber::Callback& callback,
00076 const ros::VoidPtr& tracked_object,
00077 const TransportHints& transport_hints)
00078 {
00079 return CameraSubscriber(*this, impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints);
00080 }
00081
00082 std::vector<std::string> ImageTransport::getDeclaredTransports() const
00083 {
00084 std::vector<std::string> transports = impl_->sub_loader_->getDeclaredClasses();
00085
00086 BOOST_FOREACH(std::string& transport, transports) {
00087 transport = boost::erase_last_copy(transport, "_sub");
00088 }
00089 return transports;
00090 }
00091
00092 std::vector<std::string> ImageTransport::getLoadableTransports() const
00093 {
00094 std::vector<std::string> loadableTransports;
00095
00096 BOOST_FOREACH( const std::string& transportPlugin, impl_->sub_loader_->getDeclaredClasses() )
00097 {
00098
00099
00100
00101 try
00102 {
00103 boost::shared_ptr<image_transport::SubscriberPlugin> sub = impl_->sub_loader_->createInstance(transportPlugin);
00104 loadableTransports.push_back(boost::erase_last_copy(transportPlugin, "_sub"));
00105 }
00106 catch (const pluginlib::LibraryLoadException& e) {}
00107 catch (const pluginlib::CreateClassException& e) {}
00108 }
00109
00110 return loadableTransports;
00111
00112 }
00113
00114 }