Manages a subscription callback on synchronized Image and CameraInfo topics for RGB and depth camera, and possibly also the pointcloud from depth. More...
#include <rgbd_camera_subscriber.h>
Classes | |
struct | Impl |
Public Types | |
typedef boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> | Callback |
typedef boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &, const sensor_msgs::PointCloud2ConstPtr &)> | PclCallback |
Public Member Functions | |
std::string | getDepthInfoTopic () const |
Get the depth camera info topic. More... | |
std::string | getDepthTopic () const |
Get the depth base topic (on which the raw image is published). More... | |
std::string | getDepthTransport () const |
Returns the name of the transport being used for depth. More... | |
size_t | getNumPublishers () const |
Returns the number of publishers this subscriber is connected to. More... | |
std::string | getPclTopic () const |
Get the topic of the pointcloud (can be empty if pointcloud is not processed). More... | |
std::string | getRGBInfoTopic () const |
Get the RGB camera info topic. More... | |
std::string | getRGBTopic () const |
Get the RGB base topic (on which the raw image is published). More... | |
std::string | getRGBTransport () const |
Returns the name of the transport being used for RGB. More... | |
operator void * () const | |
bool | operator!= (const RgbdCameraSubscriber &rhs) const |
bool | operator< (const RgbdCameraSubscriber &rhs) const |
bool | operator== (const RgbdCameraSubscriber &rhs) const |
RgbdCameraSubscriber () | |
void | shutdown () |
Unsubscribe the callback associated with this RgbdCameraSubscriber. More... | |
Private Member Functions | |
RgbdCameraSubscriber (RgbdImageTransport &image_it, ros::NodeHandle &rgb_nh, ros::NodeHandle &depth_nh, const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, const 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()) | |
RgbdCameraSubscriber (RgbdImageTransport &image_it, ros::NodeHandle &rgb_nh, ros::NodeHandle &depth_nh, ros::NodeHandle &pcl_nh, const std::string &rgb_base_topic, const std::string &depth_base_topic, const std::string &pcl_topic, size_t queue_size, const PclCallback &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(), const ros::TransportHints &transport_hints_pcl=ros::TransportHints()) | |
Private Attributes | |
std::shared_ptr< Impl > | impl |
Friends | |
class | RgbdImageTransport |
Manages a subscription callback on synchronized Image and CameraInfo topics for RGB and depth camera, and possibly also the pointcloud from depth.
RgbdCameraSubscriber is the client-side counterpart to CameraPublisher, and assumes the same topic naming convention. The callback is of type:
void callback(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&, const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&);
or
void callback(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&, const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&, const sensor_msgs::PointCloud2ConstPtr&);
A RgbdCameraSubscriber should always be created through a call to RgbdImageTransport::subscribeCamera(), or copied from one that was. Once all copies of a specific RgbdCameraSubscriber go out of scope, the subscription callback associated with that handle will stop being called. Once all RgbdCameraSubscriber for a given topic go out of scope the topic will be unsubscribed.
Definition at line 31 of file rgbd_camera_subscriber.h.
typedef boost::function<void(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&, const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&)> camera_throttle::RgbdCameraSubscriber::Callback |
Definition at line 37 of file rgbd_camera_subscriber.h.
typedef boost::function<void(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&, const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&, const sensor_msgs::PointCloud2ConstPtr&)> camera_throttle::RgbdCameraSubscriber::PclCallback |
Definition at line 42 of file rgbd_camera_subscriber.h.
|
inline |
Definition at line 44 of file rgbd_camera_subscriber.h.
|
private |
Definition at line 87 of file rgbd_camera_subscriber.cpp.
|
private |
Definition at line 121 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getDepthInfoTopic | ( | ) | const |
Get the depth camera info topic.
Definition at line 177 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getDepthTopic | ( | ) | const |
Get the depth base topic (on which the raw image is published).
Definition at line 171 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getDepthTransport | ( | ) | const |
Returns the name of the transport being used for depth.
Definition at line 206 of file rgbd_camera_subscriber.cpp.
size_t camera_throttle::RgbdCameraSubscriber::getNumPublishers | ( | ) | const |
Returns the number of publishers this subscriber is connected to.
Definition at line 189 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getPclTopic | ( | ) | const |
Get the topic of the pointcloud (can be empty if pointcloud is not processed).
Definition at line 183 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getRGBInfoTopic | ( | ) | const |
Get the RGB camera info topic.
Definition at line 165 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getRGBTopic | ( | ) | const |
Get the RGB base topic (on which the raw image is published).
Definition at line 159 of file rgbd_camera_subscriber.cpp.
std::string camera_throttle::RgbdCameraSubscriber::getRGBTransport | ( | ) | const |
Returns the name of the transport being used for RGB.
Definition at line 200 of file rgbd_camera_subscriber.cpp.
|
explicit |
Definition at line 217 of file rgbd_camera_subscriber.cpp.
|
inline |
Definition at line 93 of file rgbd_camera_subscriber.h.
|
inline |
Definition at line 92 of file rgbd_camera_subscriber.h.
|
inline |
Definition at line 94 of file rgbd_camera_subscriber.h.
void camera_throttle::RgbdCameraSubscriber::shutdown | ( | ) |
Unsubscribe the callback associated with this RgbdCameraSubscriber.
Definition at line 212 of file rgbd_camera_subscriber.cpp.
|
friend |
Definition at line 114 of file rgbd_camera_subscriber.h.
|
private |
Definition at line 111 of file rgbd_camera_subscriber.h.