Go to the documentation of this file.
5 #ifndef RGBD_CLIENT_ROS_BASE_H_
6 #define RGBD_CLIENT_ROS_BASE_H_
8 #include <ros/node_handle.h>
9 #include <ros/callback_queue.h>
10 #include "ros/callback_queue_interface.h"
12 #include <message_filters/synchronizer.h>
13 #include <message_filters/subscriber.h>
14 #include <message_filters/sync_policies/approximate_time.h>
15 #include <image_geometry/pinhole_camera_model.h>
17 #include <sensor_msgs/Image.h>
18 #include <sensor_msgs/CameraInfo.h>
27 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image>
RGBDApproxPolicy;
95 void camInfoCallback(
const sensor_msgs::CameraInfoConstPtr& cam_info_msg);
109 #endif // RGBD_CLIENT_ROS_BASE_H_
image_geometry::PinholeCameraModel cam_model_
std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > sub_rgb_sync_
std::unique_ptr< message_filters::Synchronizer< RGBDApproxPolicy > > sync_
ros::Subscriber sub_cam_info_
virtual ~ClientROSBase()
Destructor.
void camInfoCallback(const sensor_msgs::CameraInfoConstPtr &cam_info_msg)
Callback for CameraInfo, will unsubscribe after succesfully receiving first message.
bool initialized()
Check if the client is initialized. nextImage will not return an image if client is not initialized.
bool deinitialize()
Clears the subscribers. initialized will now return false.
bool initialize(const std::string &rgb_image_topic, const std::string &depth_image_topic, const std::string &cam_info_topic)
Initialize the subscriber.
std::shared_ptr< const Image > ImageConstPtr
ClientROSBase(ros::NodeHandle nh)
Constructor.
bool imageCallback(const sensor_msgs::ImageConstPtr &rgb_image_msg, const sensor_msgs::ImageConstPtr &depth_image_msg)
Callback for synched rgb and depth image.
std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > sub_depth_sync_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > RGBDApproxPolicy
Client which subscribes to regular ROS image topics.
bool new_image_
new_image_ Track if image is updated in a callback.
Image * image_ptr_
image_ptr_ Pointer to image. Image could be provided by reference or the pointer will be wrapped in a...