rgbd_camera_subscriber.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 #include <sensor_msgs/CameraInfo.h>
5 #include <sensor_msgs/Image.h>
6 #include <sensor_msgs/PointCloud2.h>
8 
9 namespace camera_throttle {
10 
11 class RgbdImageTransport;
12 
32 {
33 public:
34  typedef boost::function<void(const sensor_msgs::ImageConstPtr&,
35  const sensor_msgs::CameraInfoConstPtr&,
36  const sensor_msgs::ImageConstPtr&,
37  const sensor_msgs::CameraInfoConstPtr&)> Callback;
38  typedef boost::function<void(const sensor_msgs::ImageConstPtr&,
39  const sensor_msgs::CameraInfoConstPtr&,
40  const sensor_msgs::ImageConstPtr&,
41  const sensor_msgs::CameraInfoConstPtr&,
42  const sensor_msgs::PointCloud2ConstPtr&)> PclCallback;
43 
45 
49  std::string getRGBTopic() const;
50 
54  std::string getRGBInfoTopic() const;
55 
59  std::string getDepthTopic() const;
60 
64  std::string getDepthInfoTopic() const;
65 
69  std::string getPclTopic() const;
70 
74  size_t getNumPublishers() const;
75 
79  std::string getRGBTransport() const;
80 
84  std::string getDepthTransport() const;
85 
89  void shutdown();
90 
91  explicit operator void*() const;
92  bool operator< (const RgbdCameraSubscriber& rhs) const { return impl < rhs.impl; }
93  bool operator!=(const RgbdCameraSubscriber& rhs) const { return impl != rhs.impl; }
94  bool operator==(const RgbdCameraSubscriber& rhs) const { return impl == rhs.impl; }
95 
96 private:
98  const std::string& rgb_base_topic, const std::string& depth_base_topic,
99  size_t queue_size, const Callback& callback,
100  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
102  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints());
104  const std::string& rgb_base_topic, const std::string& depth_base_topic,
105  const std::string& pcl_topic, size_t queue_size, const PclCallback& callback,
106  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
108  const image_transport::TransportHints& transport_hints_depth = image_transport::TransportHints(),
109  const ros::TransportHints& transport_hints_pcl = ros::TransportHints());
110 
111  struct Impl;
112  std::shared_ptr<Impl> impl;
113 
114  friend class RgbdImageTransport;
115 };
116 
117 }
camera_throttle::RgbdCameraSubscriber::getDepthTopic
std::string getDepthTopic() const
Get the depth base topic (on which the raw image is published).
Definition: rgbd_camera_subscriber.cpp:171
camera_throttle::RgbdCameraSubscriber
Manages a subscription callback on synchronized Image and CameraInfo topics for RGB and depth camera,...
Definition: rgbd_camera_subscriber.h:31
camera_throttle::RgbdCameraSubscriber::getRGBTransport
std::string getRGBTransport() const
Returns the name of the transport being used for RGB.
Definition: rgbd_camera_subscriber.cpp:200
boost::shared_ptr< void >
camera_throttle::RgbdCameraSubscriber::operator<
bool operator<(const RgbdCameraSubscriber &rhs) const
Definition: rgbd_camera_subscriber.h:92
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::getRGBTopic
std::string getRGBTopic() const
Get the RGB base topic (on which the raw image is published).
Definition: rgbd_camera_subscriber.cpp:159
ros.h
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::RgbdCameraSubscriber::RgbdCameraSubscriber
RgbdCameraSubscriber()
Definition: rgbd_camera_subscriber.h:44
camera_throttle::RgbdCameraSubscriber::getPclTopic
std::string getPclTopic() const
Get the topic of the pointcloud (can be empty if pointcloud is not processed).
Definition: rgbd_camera_subscriber.cpp:183
camera_throttle::RgbdCameraSubscriber::shutdown
void shutdown()
Unsubscribe the callback associated with this RgbdCameraSubscriber.
Definition: rgbd_camera_subscriber.cpp:212
transport_hints.h
camera_throttle::RgbdCameraSubscriber::getDepthTransport
std::string getDepthTransport() const
Returns the name of the transport being used for depth.
Definition: rgbd_camera_subscriber.cpp:206
camera_throttle::RgbdCameraSubscriber::getNumPublishers
size_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
Definition: rgbd_camera_subscriber.cpp:189
camera_throttle::RgbdCameraSubscriber::impl
std::shared_ptr< Impl > impl
Definition: rgbd_camera_subscriber.h:111
camera_throttle::RgbdCameraSubscriber::getDepthInfoTopic
std::string getDepthInfoTopic() const
Get the depth camera info topic.
Definition: rgbd_camera_subscriber.cpp:177
camera_throttle
Definition: camera_throttle.h:11
camera_throttle::RgbdCameraSubscriber::Impl
Definition: rgbd_camera_subscriber.cpp:19
camera_throttle::RgbdCameraSubscriber::getRGBInfoTopic
std::string getRGBInfoTopic() const
Get the RGB camera info topic.
Definition: rgbd_camera_subscriber.cpp:165
camera_throttle::RgbdCameraSubscriber::operator!=
bool operator!=(const RgbdCameraSubscriber &rhs) const
Definition: rgbd_camera_subscriber.h:93
image_transport::TransportHints
camera_throttle::RgbdCameraSubscriber::operator==
bool operator==(const RgbdCameraSubscriber &rhs) const
Definition: rgbd_camera_subscriber.h:94
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