Go to the documentation of this file.
4 #include <sensor_msgs/CameraInfo.h>
5 #include <sensor_msgs/Image.h>
6 #include <sensor_msgs/PointCloud2.h>
11 class RgbdImageTransport;
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&,
91 explicit operator void*()
const;
98 const std::string& rgb_base_topic,
const std::string& depth_base_topic,
99 size_t queue_size,
const Callback& callback,
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,
112 std::shared_ptr<Impl>
impl;
std::string getDepthTopic() const
Get the depth base topic (on which the raw image is published).
Manages a subscription callback on synchronized Image and CameraInfo topics for RGB and depth camera,...
std::string getRGBTransport() const
Returns the name of the transport being used for RGB.
bool operator<(const RgbdCameraSubscriber &rhs) const
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::PointCloud2ConstPtr &)> PclCallback
std::string getRGBTopic() const
Get the RGB base topic (on which the raw image is published).
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
std::string getPclTopic() const
Get the topic of the pointcloud (can be empty if pointcloud is not processed).
void shutdown()
Unsubscribe the callback associated with this RgbdCameraSubscriber.
std::string getDepthTransport() const
Returns the name of the transport being used for depth.
size_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
std::shared_ptr< Impl > impl
std::string getDepthInfoTopic() const
Get the depth camera info topic.
std::string getRGBInfoTopic() const
Get the RGB camera info topic.
bool operator!=(const RgbdCameraSubscriber &rhs) const
bool operator==(const RgbdCameraSubscriber &rhs) const
camera_throttle
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:15