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

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

#include <client_ros_base.h>

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

Public Member Functions

 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 Member Functions

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...
 

Protected Attributes

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_
 

Detailed Description

Client which subscribes to regular ROS image topics.

Definition at line 32 of file client_ros_base.h.

Constructor & Destructor Documentation

◆ ClientROSBase()

rgbd::ClientROSBase::ClientROSBase ( ros::NodeHandle  nh)

Constructor.

Pointers are initialized to nullptr

Definition at line 17 of file client_ros_base.cpp.

◆ ~ClientROSBase()

rgbd::ClientROSBase::~ClientROSBase ( )
virtual

Destructor.

image_ptr_ is not delete as the client never owns the image pointer

Definition at line 23 of file client_ros_base.cpp.

Member Function Documentation

◆ camInfoCallback()

void rgbd::ClientROSBase::camInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  cam_info_msg)
protected

Callback for CameraInfo, will unsubscribe after succesfully receiving first message.

Parameters
cam_info_msgmessage

Definition at line 56 of file client_ros_base.cpp.

◆ deinitialize()

bool rgbd::ClientROSBase::deinitialize ( )

Clears the subscribers. initialized will now return false.

Returns
indicates success

Definition at line 44 of file client_ros_base.cpp.

◆ imageCallback()

bool rgbd::ClientROSBase::imageCallback ( const sensor_msgs::ImageConstPtr &  rgb_image_msg,
const sensor_msgs::ImageConstPtr &  depth_image_msg 
)
protected

Callback for synched rgb and depth image.

Parameters
rgb_image_msgrgb image message
depth_image_msgdepth image message
Returns
success

Definition at line 71 of file client_ros_base.cpp.

◆ initialize()

bool rgbd::ClientROSBase::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 30 of file client_ros_base.cpp.

◆ initialized()

bool rgbd::ClientROSBase::initialized ( )
inline

Check if the client is initialized. nextImage will not return an image if client is not initialized.

Returns
initialized or not

Definition at line 69 of file client_ros_base.h.

Member Data Documentation

◆ cam_model_

image_geometry::PinholeCameraModel rgbd::ClientROSBase::cam_model_
protected

Definition at line 79 of file client_ros_base.h.

◆ image_ptr_

Image* rgbd::ClientROSBase::image_ptr_
protected

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.

Definition at line 89 of file client_ros_base.h.

◆ new_image_

bool rgbd::ClientROSBase::new_image_
protected

new_image_ Track if image is updated in a callback.

Definition at line 84 of file client_ros_base.h.

◆ nh_

ros::NodeHandle rgbd::ClientROSBase::nh_
protected

Definition at line 73 of file client_ros_base.h.

◆ sub_cam_info_

ros::Subscriber rgbd::ClientROSBase::sub_cam_info_
protected

Definition at line 78 of file client_ros_base.h.

◆ sub_depth_sync_

std::unique_ptr<message_filters::Subscriber<sensor_msgs::Image> > rgbd::ClientROSBase::sub_depth_sync_
protected

Definition at line 77 of file client_ros_base.h.

◆ sub_rgb_sync_

std::unique_ptr<message_filters::Subscriber<sensor_msgs::Image> > rgbd::ClientROSBase::sub_rgb_sync_
protected

Definition at line 76 of file client_ros_base.h.

◆ sync_

std::unique_ptr<message_filters::Synchronizer<RGBDApproxPolicy> > rgbd::ClientROSBase::sync_
protected

Definition at line 75 of file client_ros_base.h.


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