Go to the documentation of this file.
   39 int main(
int argc, 
char** argv)
 
   43     printf(
"Usage: %s in_transport in:=<in_base_topic> [out_transport] out:=<out_base_topic>\n", argv[0]);
 
   48   std::string in_transport = argv[1];
 
   61     sub = it.
subscribe(in_topic, 1, boost::bind(pub_mem_fn, &pub, boost::placeholders::_1), 
ros::VoidPtr(), in_transport);
 
   67     std::string out_transport = argv[2];
 
   72     std::string lookup_name = Plugin::getLookupName(out_transport);
 
   78     typedef void (Plugin::*PublishMemFn)(
const sensor_msgs::ImageConstPtr&) 
const;
 
   79     PublishMemFn pub_mem_fn = &Plugin::publish;
 
   80     sub = it.
subscribe(in_topic, 1, boost::bind(pub_mem_fn, pub.get(), boost::placeholders::_1), pub, in_transport);
 
  
Advertise and subscribe to image topics.
Manages advertisements of multiple transport options on an Image topic.
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
std::string resolveName(const std::string &name, bool remap=true) const
Manages a subscription callback on a specific topic that can be interpreted as an Image topic.
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.
void publish(const sensor_msgs::Image &message) const
Publish an image on the topics associated with this Publisher.
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Base class for plugins to Publisher.
int main(int argc, char **argv)
boost::shared_ptr< void > VoidPtr
image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Apr 11 2025 02:14:22