Client which subscribes to regular ROS image topics.
More...
#include <client_ros_base.h>
|
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...
|
|
Client which subscribes to regular ROS image topics.
Definition at line 32 of file client_ros_base.h.
◆ ClientROSBase()
rgbd::ClientROSBase::ClientROSBase |
( |
ros::NodeHandle |
nh | ) |
|
◆ ~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.
◆ camInfoCallback()
void rgbd::ClientROSBase::camInfoCallback |
( |
const sensor_msgs::CameraInfoConstPtr & |
cam_info_msg | ) |
|
|
protected |
Callback for CameraInfo, will unsubscribe after succesfully receiving first message.
- Parameters
-
Definition at line 56 of file client_ros_base.cpp.
◆ deinitialize()
bool rgbd::ClientROSBase::deinitialize |
( |
| ) |
|
◆ 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_msg | rgb image message |
depth_image_msg | depth image message |
- Returns
- success
Definition at line 71 of file client_ros_base.cpp.
◆ initialize()
Initialize the subscriber.
- Parameters
-
rgb_image_topic | topic name of the rgb image; topic will still be resolved. |
depth_image_topic | topic name of the depth image; topic will still be resolved. |
cam_info_topic | topic 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.
◆ cam_model_
image_geometry::PinholeCameraModel rgbd::ClientROSBase::cam_model_ |
|
protected |
◆ 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 |
◆ sub_cam_info_
ros::Subscriber rgbd::ClientROSBase::sub_cam_info_ |
|
protected |
◆ sub_depth_sync_
std::unique_ptr<message_filters::Subscriber<sensor_msgs::Image> > rgbd::ClientROSBase::sub_depth_sync_ |
|
protected |
◆ sub_rgb_sync_
std::unique_ptr<message_filters::Subscriber<sensor_msgs::Image> > rgbd::ClientROSBase::sub_rgb_sync_ |
|
protected |
◆ sync_
The documentation for this class was generated from the following files: