rgbd
client_ros_base.h
Go to the documentation of this file.
1 
5 #ifndef RGBD_CLIENT_ROS_BASE_H_
6 #define RGBD_CLIENT_ROS_BASE_H_
7 
8 #include <ros/node_handle.h>
9 #include <ros/callback_queue.h>
10 #include "ros/callback_queue_interface.h"
11 
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>
16 
17 #include <sensor_msgs/Image.h>
18 #include <sensor_msgs/CameraInfo.h>
19 
20 #include "rgbd/types.h"
21 
22 #include <memory>
23 
24 
25 namespace rgbd {
26 
27 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> RGBDApproxPolicy;
28 
33 
34 public:
35 
41  ClientROSBase(ros::NodeHandle nh);
42 
48  virtual ~ClientROSBase();
49 
57  bool initialize(const std::string& rgb_image_topic, const std::string& depth_image_topic, const std::string& cam_info_topic);
58 
63  bool deinitialize();
64 
69  bool initialized() { return bool(sync_); }
70 
71 protected:
72 
73  ros::NodeHandle nh_;
74 
78  ros::Subscriber sub_cam_info_;
79  image_geometry::PinholeCameraModel cam_model_;
80 
84  bool new_image_;
90 
95  void camInfoCallback(const sensor_msgs::CameraInfoConstPtr& cam_info_msg);
96 
103  bool imageCallback(const sensor_msgs::ImageConstPtr& rgb_image_msg, const sensor_msgs::ImageConstPtr& depth_image_msg);
104 
105 };
106 
107 }
108 
109 #endif // RGBD_CLIENT_ROS_BASE_H_
rgbd::ClientROSBase::cam_model_
image_geometry::PinholeCameraModel cam_model_
Definition: client_ros_base.h:79
rgbd::ClientROSBase::sub_rgb_sync_
std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > sub_rgb_sync_
Definition: client_ros_base.h:76
std::string
rgbd::ClientROSBase::sync_
std::unique_ptr< message_filters::Synchronizer< RGBDApproxPolicy > > sync_
Definition: client_ros_base.h:75
types.h
rgbd::ClientROSBase::sub_cam_info_
ros::Subscriber sub_cam_info_
Definition: client_ros_base.h:78
rgbd::ClientROSBase::~ClientROSBase
virtual ~ClientROSBase()
Destructor.
Definition: client_ros_base.cpp:23
rgbd::ClientROSBase::camInfoCallback
void camInfoCallback(const sensor_msgs::CameraInfoConstPtr &cam_info_msg)
Callback for CameraInfo, will unsubscribe after succesfully receiving first message.
Definition: client_ros_base.cpp:56
rgbd::ClientROSBase::initialized
bool initialized()
Check if the client is initialized. nextImage will not return an image if client is not initialized.
Definition: client_ros_base.h:69
rgbd::ClientROSBase::deinitialize
bool deinitialize()
Clears the subscribers. initialized will now return false.
Definition: client_ros_base.cpp:44
rgbd::ClientROSBase::nh_
ros::NodeHandle nh_
Definition: client_ros_base.h:73
rgbd::Image
Definition: image.h:43
rgbd::ClientROSBase::initialize
bool initialize(const std::string &rgb_image_topic, const std::string &depth_image_topic, const std::string &cam_info_topic)
Initialize the subscriber.
Definition: client_ros_base.cpp:30
rgbd
Definition: client.h:24
rgbd::ImageConstPtr
std::shared_ptr< const Image > ImageConstPtr
Definition: types.h:10
rgbd::ClientROSBase::ClientROSBase
ClientROSBase(ros::NodeHandle nh)
Constructor.
Definition: client_ros_base.cpp:17
memory
rgbd::ClientROSBase::imageCallback
bool imageCallback(const sensor_msgs::ImageConstPtr &rgb_image_msg, const sensor_msgs::ImageConstPtr &depth_image_msg)
Callback for synched rgb and depth image.
Definition: client_ros_base.cpp:71
rgbd::ClientROSBase::sub_depth_sync_
std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > sub_depth_sync_
Definition: client_ros_base.h:77
rgbd::RGBDApproxPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > RGBDApproxPolicy
Definition: client_ros_base.h:27
rgbd::ClientROSBase
Client which subscribes to regular ROS image topics.
Definition: client_ros_base.h:32
rgbd::ClientROSBase::new_image_
bool new_image_
new_image_ Track if image is updated in a callback.
Definition: client_ros_base.h:84
std::unique_ptr
rgbd::ClientROSBase::image_ptr_
Image * image_ptr_
image_ptr_ Pointer to image. Image could be provided by reference or the pointer will be wrapped in a...
Definition: client_ros_base.h:89