rgbd_image_transport.cpp
Go to the documentation of this file.
2 
3 namespace camera_throttle
4 {
5 
6 RgbdImageTransport::RgbdImageTransport(const ros::NodeHandle& rgbNh, const ros::NodeHandle& depthNh) : rgbNh(rgbNh), depthNh(depthNh), ImageTransport(rgbNh)
7 {
8 }
9 
10 RgbdImageTransport::RgbdImageTransport(const ros::NodeHandle& rgbNh, const ros::NodeHandle& depthNh, const ros::NodeHandle& pclNh) : rgbNh(rgbNh), depthNh(depthNh), pclNh(pclNh), ImageTransport(rgbNh)
11 {
12 }
13 
14 RgbdCameraPublisher RgbdImageTransport::advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
15  size_t queue_size, bool latch)
16 {
17  return advertiseRgbdCamera(rgb_base_topic, depth_base_topic, queue_size,
22  ros::VoidPtr(), latch);
23 }
24 
25 RgbdCameraPublisher RgbdImageTransport::advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
26  size_t queue_size,
27  const image_transport::SubscriberStatusCallback& rgb_connect_cb,
28  const image_transport::SubscriberStatusCallback& rgb_disconnect_cb,
29  const image_transport::SubscriberStatusCallback& depth_connect_cb,
30  const image_transport::SubscriberStatusCallback& depth_disconnect_cb,
31  const ros::SubscriberStatusCallback& rgb_info_connect_cb,
32  const ros::SubscriberStatusCallback& rgb_info_disconnect_cb,
33  const ros::SubscriberStatusCallback& depth_info_connect_cb,
34  const ros::SubscriberStatusCallback& depth_info_disconnect_cb,
35  const ros::VoidPtr& tracked_object, bool latch)
36 {
37  return RgbdCameraPublisher(*this, this->rgbNh, this->depthNh, rgb_base_topic, depth_base_topic, queue_size,
38  rgb_connect_cb, rgb_disconnect_cb, depth_connect_cb, depth_disconnect_cb,
39  rgb_info_connect_cb, rgb_info_disconnect_cb, depth_info_connect_cb, depth_info_disconnect_cb,
40  tracked_object, latch);
41 }
42 
43 RgbdCameraPublisher RgbdImageTransport::advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
44  const std::string& pcl_topic, size_t queue_size, bool latch)
45 {
46  return advertiseRgbdCamera(rgb_base_topic, depth_base_topic, pcl_topic, queue_size,
52  ros::VoidPtr(), latch);
53 }
54 
55 RgbdCameraPublisher RgbdImageTransport::advertiseRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
56  const std::string& pcl_topic, size_t queue_size,
57  const image_transport::SubscriberStatusCallback& rgb_connect_cb,
58  const image_transport::SubscriberStatusCallback& rgb_disconnect_cb,
59  const image_transport::SubscriberStatusCallback& depth_connect_cb,
60  const image_transport::SubscriberStatusCallback& depth_disconnect_cb,
61  const ros::SubscriberStatusCallback& pcl_connect_cb,
62  const ros::SubscriberStatusCallback& pcl_disconnect_cb,
63  const ros::SubscriberStatusCallback& rgb_info_connect_cb,
64  const ros::SubscriberStatusCallback& rgb_info_disconnect_cb,
65  const ros::SubscriberStatusCallback& depth_info_connect_cb,
66  const ros::SubscriberStatusCallback& depth_info_disconnect_cb,
67  const ros::VoidPtr& tracked_object, bool latch)
68 {
69  return RgbdCameraPublisher(*this, this->rgbNh, this->depthNh, this->pclNh, rgb_base_topic, depth_base_topic, pcl_topic, queue_size,
70  rgb_connect_cb, rgb_disconnect_cb, depth_connect_cb, depth_disconnect_cb, pcl_connect_cb, pcl_disconnect_cb,
71  rgb_info_connect_cb, rgb_info_disconnect_cb, depth_info_connect_cb, depth_info_disconnect_cb,
72  tracked_object, latch);
73 }
74 
75 RgbdCameraSubscriber RgbdImageTransport::subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic, size_t queue_size,
76  const RgbdCameraSubscriber::Callback& callback,
77  const ros::VoidPtr& tracked_object,
78  const image_transport::TransportHints& transport_hints_rgb,
79  const image_transport::TransportHints& transport_hints_depth)
80 {
81  return RgbdCameraSubscriber(*this, this->rgbNh, this->depthNh, rgb_base_topic, depth_base_topic, queue_size, callback, tracked_object, transport_hints_rgb, transport_hints_depth);
82 }
83 
84 RgbdCameraSubscriber RgbdImageTransport::subscribeRgbdCamera(const std::string& rgb_base_topic, const std::string& depth_base_topic,
85  const std::string& pcl_topic, size_t queue_size,
86  const RgbdCameraSubscriber::PclCallback& callback,
87  const ros::VoidPtr& tracked_object,
88  const image_transport::TransportHints& transport_hints_rgb,
89  const image_transport::TransportHints& transport_hints_depth,
90  const ros::TransportHints& transport_hints_pcl)
91 {
92  return RgbdCameraSubscriber(*this, this->rgbNh, this->depthNh, this->pclNh, rgb_base_topic, depth_base_topic, pcl_topic, queue_size, callback, tracked_object, transport_hints_rgb, transport_hints_depth, transport_hints_pcl);
93 }
94 
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
boost::shared_ptr< void >
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
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::RgbdImageTransport
RgbdImageTransport(const ros::NodeHandle &rgbNh, const ros::NodeHandle &depthNh)
Definition: rgbd_image_transport.cpp:6
rgbd_image_transport.h
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
camera_throttle
Definition: camera_throttle.h:11
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
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
ros::NodeHandle


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