rgbd_image_transport.h
Go to the documentation of this file.
1 #pragma once
2 
6 
7 namespace camera_throttle
8 {
9 
11 {
14  public: virtual ~RgbdImageTransport() = default;
15 
19  public: RgbdCameraPublisher advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
20  size_t queue_size, bool latch = false);
21 
26  public: RgbdCameraPublisher advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
27  size_t queue_size,
28  const image_transport::SubscriberStatusCallback& rgb_connect_cb,
32  const ros::SubscriberStatusCallback& rgb_info_connect_cb = ros::SubscriberStatusCallback(),
33  const ros::SubscriberStatusCallback& rgb_info_disconnect_cb = ros::SubscriberStatusCallback(),
34  const ros::SubscriberStatusCallback& depth_info_connect_cb = ros::SubscriberStatusCallback(),
35  const ros::SubscriberStatusCallback& depth_info_disconnect_cb = ros::SubscriberStatusCallback(),
36  const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
37 
41  public: RgbdCameraPublisher advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
42  const std::string& pcl_topic, size_t queue_size, bool latch = false);
43 
48  public: RgbdCameraPublisher advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
49  const std::string& pcl_topic, size_t queue_size,
50  const image_transport::SubscriberStatusCallback& rgb_connect_cb,
56  const ros::SubscriberStatusCallback& rgb_info_connect_cb = ros::SubscriberStatusCallback(),
57  const ros::SubscriberStatusCallback& rgb_info_disconnect_cb = ros::SubscriberStatusCallback(),
58  const ros::SubscriberStatusCallback& depth_info_connect_cb = ros::SubscriberStatusCallback(),
59  const ros::SubscriberStatusCallback& depth_info_disconnect_cb = ros::SubscriberStatusCallback(),
60  const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
61 
69  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic, size_t queue_size,
70  const RgbdCameraSubscriber::Callback& callback,
71  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
73  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints());
74 
78  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic, size_t queue_size,
79  void(*fp)(const sensor_msgs::ImageConstPtr&,
80  const sensor_msgs::CameraInfoConstPtr&,
81  const sensor_msgs::ImageConstPtr&,
82  const sensor_msgs::CameraInfoConstPtr&),
85  {
86  return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, queue_size, RgbdCameraSubscriber::Callback(fp), ros::VoidPtr(),
87  transport_hints_rgb, transport_hints_depth);
88  }
89 
94  template<class T>
95  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic, size_t queue_size,
96  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
97  const sensor_msgs::CameraInfoConstPtr&,
98  const sensor_msgs::ImageConstPtr&,
99  const sensor_msgs::CameraInfoConstPtr&), T* obj,
101  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints())
102  {
103  return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, queue_size, boost::bind(fp, obj, _1, _2, _3, _4), ros::VoidPtr(),
104  transport_hints_rgb, transport_hints_depth);
105  }
106 
111  template<class T>
112  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic, size_t queue_size,
113  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
114  const sensor_msgs::CameraInfoConstPtr&,
115  const sensor_msgs::ImageConstPtr&,
116  const sensor_msgs::CameraInfoConstPtr&),
117  const boost::shared_ptr<T>& obj,
119  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints())
120  {
121  return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, queue_size, boost::bind(fp, obj.get(), _1, _2, _3, _4), obj,
122  transport_hints_rgb, transport_hints_depth);
123  }
124 
125 
126 
134  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
135  const std::string& pcl_topic, size_t queue_size,
136  const RgbdCameraSubscriber::PclCallback& callback,
137  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
139  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints(),
140  const ros::TransportHints& transport_hints_pcl = ros::TransportHints());
141 
145  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
146  const std::string& pcl_topic, size_t queue_size,
147  void(*fp)(const sensor_msgs::ImageConstPtr&,
148  const sensor_msgs::CameraInfoConstPtr&,
149  const sensor_msgs::ImageConstPtr&,
150  const sensor_msgs::CameraInfoConstPtr&,
151  const sensor_msgs::PointCloud2ConstPtr&),
153  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints(),
154  const ros::TransportHints& transport_hints_pcl = ros::TransportHints())
155  {
156  return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, pcl_topic, queue_size, RgbdCameraSubscriber::PclCallback(fp), ros::VoidPtr(),
157  transport_hints_rgb, transport_hints_depth, transport_hints_pcl);
158  }
159 
164  template<class T>
165  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
166  const std::string& pcl_topic, size_t queue_size,
167  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
168  const sensor_msgs::CameraInfoConstPtr&,
169  const sensor_msgs::ImageConstPtr&,
170  const sensor_msgs::CameraInfoConstPtr&,
171  const sensor_msgs::PointCloud2ConstPtr&), T* obj,
173  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints(),
174  const ros::TransportHints& transport_hints_pcl = ros::TransportHints())
175  {
176  return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, pcl_topic, queue_size, boost::bind(fp, obj, _1, _2, _3, _4, _5), ros::VoidPtr(),
177  transport_hints_rgb, transport_hints_depth, transport_hints_pcl);
178  }
179 
184  template<class T>
185  RgbdCameraSubscriber subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
186  const std::string& pcl_topic, size_t queue_size,
187  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
188  const sensor_msgs::CameraInfoConstPtr&,
189  const sensor_msgs::ImageConstPtr&,
190  const sensor_msgs::CameraInfoConstPtr&,
191  const sensor_msgs::PointCloud2ConstPtr&),
192  const boost::shared_ptr<T>& obj,
194  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints(),
195  const ros::TransportHints& transport_hints_pcl = ros::TransportHints())
196  {
197  return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, pcl_topic, queue_size, boost::bind(fp, obj.get(), _1, _2, _3, _4, _5), obj,
198  transport_hints_rgb, transport_hints_depth, transport_hints_pcl);
199  }
200 
201  protected: ros::NodeHandle rgbNh;
203  protected: ros::NodeHandle pclNh;
204 };
205 
206 }
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), T *obj, const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with ba...
Definition: rgbd_image_transport.h:95
camera_throttle::RgbdCameraSubscriber
Manages a subscription callback on synchronized Image and CameraInfo topics for RGB and depth camera,...
Definition: rgbd_camera_subscriber.h:31
image_transport::ImageTransport
boost::shared_ptr< void >
camera_throttle::RgbdImageTransport::~RgbdImageTransport
virtual ~RgbdImageTransport()=default
camera_throttle::RgbdCameraSubscriber::PclCallback
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::PointCloud2ConstPtr &)> PclCallback
Definition: rgbd_camera_subscriber.h:42
camera_throttle::RgbdCameraSubscriber::Callback
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Definition: rgbd_camera_subscriber.h:37
rgbd_camera_publisher.h
ros::TransportHints
camera_throttle::RgbdImageTransport::pclNh
ros::NodeHandle pclNh
Definition: rgbd_image_transport.h:203
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, const RgbdCameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function obj...
Definition: rgbd_image_transport.cpp:75
camera_throttle::RgbdImageTransport::depthNh
ros::NodeHandle depthNh
Definition: rgbd_image_transport.h:202
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const boost::shared_ptr< T > &obj, const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with sh...
Definition: rgbd_image_transport.h:112
camera_throttle::RgbdImageTransport::RgbdImageTransport
RgbdImageTransport(const ros::NodeHandle &rgbNh, const ros::NodeHandle &depthNh)
Definition: rgbd_image_transport.cpp:6
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, const std::string &pcl_topic, size_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::PointCloud2ConstPtr &), const boost::shared_ptr< T > &obj, const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints(), const ros::TransportHints &transport_hints_pcl=ros::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with sh...
Definition: rgbd_image_transport.h:185
camera_throttle::RgbdImageTransport::advertiseRgbdCamera
RgbdCameraPublisher advertiseRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, bool latch=false)
Advertise a synchronized RGBD camera raw image + info topic pair, simple version.
Definition: rgbd_image_transport.cpp:14
image_transport.h
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, const std::string &pcl_topic, size_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::PointCloud2ConstPtr &), T *obj, const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints(), const ros::TransportHints &transport_hints_pcl=ros::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with ba...
Definition: rgbd_image_transport.h:165
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, const std::string &pcl_topic, size_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::PointCloud2ConstPtr &), const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints(), const ros::TransportHints &transport_hints_pcl=ros::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for bare function.
Definition: rgbd_image_transport.h:145
camera_throttle
Definition: camera_throttle.h:11
camera_throttle::RgbdImageTransport::subscribeRgbdCamera
RgbdCameraSubscriber subscribeRgbdCamera(const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const image_transport::TransportHints &transport_hints_rgb=image_transport::TransportHints(), const image_transport::TransportHints &transport_hints_depth=image_transport::TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for bare function.
Definition: rgbd_image_transport.h:78
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
rgbd_camera_subscriber.h
image_transport::TransportHints
camera_throttle::RgbdCameraPublisher
Manages advertisements for publishing RGBD camera images.
Definition: rgbd_camera_publisher.h:30
camera_throttle::RgbdImageTransport::rgbNh
ros::NodeHandle rgbNh
Definition: rgbd_image_transport.h:201
camera_throttle::RgbdImageTransport
Definition: rgbd_image_transport.h:10
ros::NodeHandle


camera_throttle
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:15