rgbd
Public Member Functions | Protected Attributes | List of all members
rgbd::ClientROS Class Reference

Client which subscribes to regular ROS image topics. More...

#include <client_ros.h>

Inheritance diagram for rgbd::ClientROS:
Inheritance graph
[legend]

Public Member Functions

 ClientROS ()
 Constructor. More...
 
bool initialize (const std::string &rgb_image_topic, const std::string &depth_image_topic, const std::string &cam_info_topic)
 Initialize the subscriber. More...
 
ImagePtr nextImage ()
 Get a new Image. If no new image has been received since the last call, The ImagePtr will be a nullptr. More...
 
bool nextImage (Image &image)
 Get a new Image. If no new image has been received since the last call, no image will be written and false will be returned. More...
 
virtual ~ClientROS ()
 Destructor. More...
 
- Public Member Functions inherited from rgbd::ClientROSBase
 ClientROSBase (ros::NodeHandle nh)
 Constructor. More...
 
bool deinitialize ()
 Clears the subscribers. initialized will now return false. More...
 
bool initialize (const std::string &rgb_image_topic, const std::string &depth_image_topic, const std::string &cam_info_topic)
 Initialize the subscriber. More...
 
bool initialized ()
 Check if the client is initialized. nextImage will not return an image if client is not initialized. More...
 
virtual ~ClientROSBase ()
 Destructor. More...
 

Protected Attributes

ros::CallbackQueue cb_queue_
 
- Protected Attributes inherited from rgbd::ClientROSBase
image_geometry::PinholeCameraModel cam_model_
 
Imageimage_ptr_
 image_ptr_ Pointer to image. Image could be provided by reference or the pointer will be wrapped in a shared_ptr. Either this class will never take ownership. More...
 
bool new_image_
 new_image_ Track if image is updated in a callback. More...
 
ros::NodeHandle nh_
 
ros::Subscriber sub_cam_info_
 
std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > sub_depth_sync_
 
std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > sub_rgb_sync_
 
std::unique_ptr< message_filters::Synchronizer< RGBDApproxPolicy > > sync_
 

Additional Inherited Members

- Protected Member Functions inherited from rgbd::ClientROSBase
void camInfoCallback (const sensor_msgs::CameraInfoConstPtr &cam_info_msg)
 Callback for CameraInfo, will unsubscribe after succesfully receiving first message. More...
 
bool imageCallback (const sensor_msgs::ImageConstPtr &rgb_image_msg, const sensor_msgs::ImageConstPtr &depth_image_msg)
 Callback for synched rgb and depth image. More...
 

Detailed Description

Client which subscribes to regular ROS image topics.

Definition at line 31 of file client_ros.h.

Constructor & Destructor Documentation

◆ ClientROS()

rgbd::ClientROS::ClientROS ( )

Constructor.

Definition at line 17 of file client_ros.cpp.

◆ ~ClientROS()

rgbd::ClientROS::~ClientROS ( )
virtual

Destructor.

Definition at line 23 of file client_ros.cpp.

Member Function Documentation

◆ initialize()

bool rgbd::ClientROS::initialize ( const std::string rgb_image_topic,
const std::string depth_image_topic,
const std::string cam_info_topic 
)

Initialize the subscriber.

Parameters
rgb_image_topictopic name of the rgb image; topic will still be resolved.
depth_image_topictopic name of the depth image; topic will still be resolved.
cam_info_topictopic name of the camera info; topic will still be resolved.
Returns
indicates success

Definition at line 29 of file client_ros.cpp.

◆ nextImage() [1/2]

ImagePtr rgbd::ClientROS::nextImage ( )

Get a new Image. If no new image has been received since the last call, The ImagePtr will be a nullptr.

Returns
ImagePtr to an Image or a nullptr

Definition at line 53 of file client_ros.cpp.

◆ nextImage() [2/2]

bool rgbd::ClientROS::nextImage ( Image image)

Get a new Image. If no new image has been received since the last call, no image will be written and false will be returned.

Parameters
imageImage reference which will be written.
Returns
valid image written

Definition at line 43 of file client_ros.cpp.

Member Data Documentation

◆ cb_queue_

ros::CallbackQueue rgbd::ClientROS::cb_queue_
protected

Definition at line 71 of file client_ros.h.


The documentation for this class was generated from the following files: