Go to the documentation of this file.
5 #ifndef RGBD_CLIENT_RGBD_H_
6 #define RGBD_CLIENT_RGBD_H_
8 #include <ros/node_handle.h>
9 #include <ros/subscriber.h>
10 #include <ros/callback_queue.h>
14 #include "rgbd_msgs/RGBD.h"
95 #endif // RGBD_CLIENT_RGBD_H_
bool new_image_
Track if image is updated in a callback.
virtual ~ClientRGBD()
Destructor.
bool initialized()
Check if the client is initialized. nextImage will not return an image if client is not initialized.
Image * image_ptr_
Pointer to the Image being written in the NextImage calls. Either set to the address of the provided ...
bool initialize(const std::string &server_name)
Initialize the client.
ros::Subscriber sub_image_
bool deinitialize()
Clears the subscriber. initialized will now return false.
void rgbdImageCallback(const rgbd_msgs::RGBD::ConstPtr &msg)
Client which subscribes to RGBD topic.
ros::CallbackQueue cb_queue_
ImagePtr nextImage()
Get a new Image. If no new image has been received since the last call, The ImagePtr will be a nullpt...