rgbd_camera_publisher.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <sensor_msgs/Image.h>
4 #include <sensor_msgs/CameraInfo.h>
5 #include <sensor_msgs/PointCloud2.h>
6 
7 #include <ros/ros.h>
9 
10 namespace camera_throttle
11 {
12 
13 class RgbdImageTransport;
14 
31 {
32 public:
33  RgbdCameraPublisher() = default;
34  virtual ~RgbdCameraPublisher() = default;
35 
42  size_t getNumSubscribers() const;
43 
47  std::string getRGBTopic() const;
48 
52  std::string getRGBInfoTopic() const;
53 
57  std::string getDepthTopic() const;
58 
62  std::string getDepthInfoTopic() const;
63 
67  std::string getPclTopic() const;
68 
72  void publish(const sensor_msgs::Image& rgb_image, const sensor_msgs::CameraInfo& rgb_info,
73  const sensor_msgs::Image& depth_image, const sensor_msgs::CameraInfo& depth_info) const;
74 
78  void publish(const sensor_msgs::Image& rgb_image, const sensor_msgs::CameraInfo& rgb_info,
79  const sensor_msgs::Image& depth_image, const sensor_msgs::CameraInfo& depth_info,
80  const sensor_msgs::PointCloud2& pcl) const;
81 
85  void publish(const sensor_msgs::ImageConstPtr& rgb_image, const sensor_msgs::CameraInfoConstPtr& rgb_info,
86  const sensor_msgs::ImageConstPtr& depth_image, const sensor_msgs::CameraInfoConstPtr& depth_info) const;
87 
91  void publish(const sensor_msgs::ImageConstPtr& rgb_image, const sensor_msgs::CameraInfoConstPtr& rgb_info,
92  const sensor_msgs::ImageConstPtr& depth_image, const sensor_msgs::CameraInfoConstPtr& depth_info,
93  const sensor_msgs::PointCloud2ConstPtr& pcl) const;
94 
102  void publish(sensor_msgs::Image& rgb_image, sensor_msgs::CameraInfo& rgb_info,
103  sensor_msgs::Image& depth_image, sensor_msgs::CameraInfo& depth_info, ros::Time stamp) const;
104 
112  void publish(sensor_msgs::Image& rgb_image, sensor_msgs::CameraInfo& rgb_info,
113  sensor_msgs::Image& depth_image, sensor_msgs::CameraInfo& depth_info,
114  sensor_msgs::PointCloud2& pcl, ros::Time stamp) const;
115 
119  void shutdown();
120 
121  explicit operator void*() const;
122  bool operator< (const RgbdCameraPublisher& rhs) const { return impl < rhs.impl; }
123  bool operator!=(const RgbdCameraPublisher& rhs) const { return impl != rhs.impl; }
124  bool operator==(const RgbdCameraPublisher& rhs) const { return impl == rhs.impl; }
125 
126 private:
128  const std::string& rgb_base_topic, const std::string& depth_base_topic, size_t queue_size,
129  const image_transport::SubscriberStatusCallback& rgb_connect_cb,
130  const image_transport::SubscriberStatusCallback& rgb_disconnect_cb,
131  const image_transport::SubscriberStatusCallback& depth_connect_cb,
132  const image_transport::SubscriberStatusCallback& depth_disconnect_cb,
133  const ros::SubscriberStatusCallback& rgb_info_connect_cb,
134  const ros::SubscriberStatusCallback& rgb_info_disconnect_cb,
135  const ros::SubscriberStatusCallback& depth_info_connect_cb,
136  const ros::SubscriberStatusCallback& depth_info_disconnect_cb,
137  const ros::VoidPtr& tracked_object, bool latch);
138 
140  const std::string& rgb_base_topic, const std::string& depth_base_topic, const std::string& pcl_topic,
141  size_t queue_size,
142  const image_transport::SubscriberStatusCallback& rgb_connect_cb,
143  const image_transport::SubscriberStatusCallback& rgb_disconnect_cb,
144  const image_transport::SubscriberStatusCallback& depth_connect_cb,
145  const image_transport::SubscriberStatusCallback& depth_disconnect_cb,
146  const ros::SubscriberStatusCallback& pcl_connect_cb,
147  const ros::SubscriberStatusCallback& pcl_disconnect_cb,
148  const ros::SubscriberStatusCallback& rgb_info_connect_cb,
149  const ros::SubscriberStatusCallback& rgb_info_disconnect_cb,
150  const ros::SubscriberStatusCallback& depth_info_connect_cb,
151  const ros::SubscriberStatusCallback& depth_info_disconnect_cb,
152  const ros::VoidPtr& tracked_object, bool latch);
153 
154  struct Impl;
155  std::shared_ptr<Impl> impl;
156 
157  friend class RgbdImageTransport;
158 };
159 
160 }
camera_throttle::RgbdCameraPublisher::shutdown
void shutdown()
Shutdown the advertisements associated with this Publisher.
Definition: rgbd_camera_publisher.cpp:255
boost::shared_ptr< void >
camera_throttle::RgbdCameraPublisher::getDepthInfoTopic
std::string getDepthInfoTopic() const
Returns the depth camera info topic of this CameraPublisher.
Definition: rgbd_camera_publisher.cpp:143
ros.h
camera_throttle::RgbdCameraPublisher::getPclTopic
std::string getPclTopic() const
Get the topic of the pointcloud (can be empty if pointcloud is not processed).
Definition: rgbd_camera_publisher.cpp:149
camera_throttle::RgbdCameraPublisher::operator==
bool operator==(const RgbdCameraPublisher &rhs) const
Definition: rgbd_camera_publisher.h:124
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
camera_throttle::RgbdCameraPublisher::publish
void publish(const sensor_msgs::Image &rgb_image, const sensor_msgs::CameraInfo &rgb_info, const sensor_msgs::Image &depth_image, const sensor_msgs::CameraInfo &depth_info) const
Publish an RGB and depth (image, info) pair on the topics associated with this RgbdCameraPublisher.
Definition: rgbd_camera_publisher.cpp:155
camera_throttle::RgbdCameraPublisher::~RgbdCameraPublisher
virtual ~RgbdCameraPublisher()=default
camera_throttle::RgbdCameraPublisher::getRGBTopic
std::string getRGBTopic() const
Returns the RGB base (image) topic of this CameraPublisher.
Definition: rgbd_camera_publisher.cpp:125
camera_throttle::RgbdCameraPublisher::getRGBInfoTopic
std::string getRGBInfoTopic() const
Returns the RGB camera info topic of this CameraPublisher.
Definition: rgbd_camera_publisher.cpp:131
image_transport.h
camera_throttle::RgbdCameraPublisher::operator<
bool operator<(const RgbdCameraPublisher &rhs) const
Definition: rgbd_camera_publisher.h:122
camera_throttle::RgbdCameraPublisher::Impl
Definition: rgbd_camera_publisher.cpp:8
ros::Time
camera_throttle::RgbdCameraPublisher::getDepthTopic
std::string getDepthTopic() const
Returns the depth base (image) topic of this CameraPublisher.
Definition: rgbd_camera_publisher.cpp:137
camera_throttle
Definition: camera_throttle.h:11
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
camera_throttle::RgbdCameraPublisher::operator!=
bool operator!=(const RgbdCameraPublisher &rhs) const
Definition: rgbd_camera_publisher.h:123
camera_throttle::RgbdCameraPublisher
Manages advertisements for publishing RGBD camera images.
Definition: rgbd_camera_publisher.h:30
camera_throttle::RgbdCameraPublisher::impl
std::shared_ptr< Impl > impl
Definition: rgbd_camera_publisher.h:154
camera_throttle::RgbdCameraPublisher::RgbdCameraPublisher
RgbdCameraPublisher()=default
camera_throttle::RgbdImageTransport
Definition: rgbd_image_transport.h:10
ros::NodeHandle
camera_throttle::RgbdCameraPublisher::getNumSubscribers
size_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this CameraPublisher.
Definition: rgbd_camera_publisher.cpp:115


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