rgbd
client_ros.cpp
Go to the documentation of this file.
1 #include "rgbd/client_ros.h"
2 #include "rgbd/image.h"
3 
4 // ROS message serialization
5 #include <cv_bridge/cv_bridge.h>
6 #include <message_filters/synchronizer.h>
7 #include <message_filters/subscriber.h>
8 #include <message_filters/sync_policies/approximate_time.h>
9 #include <sensor_msgs/Image.h>
10 #include <sensor_msgs/image_encodings.h>
11 #include <image_geometry/pinhole_camera_model.h>
12 
13 namespace rgbd {
14 
15 // ----------------------------------------------------------------------------------------
16 
17 ClientROS::ClientROS() : ClientROSBase(ros::NodeHandle())
18 {
19 }
20 
21 // ----------------------------------------------------------------------------------------
22 
24 {
25 }
26 
27 // ----------------------------------------------------------------------------------------
28 
29 bool ClientROS::initialize(const std::string& rgb_image_topic, const std::string& depth_image_topic, const std::string& cam_info_topic)
30 {
31  nh_.setCallbackQueue(&cb_queue_);
32 
33  if (!ClientROSBase::initialize(rgb_image_topic, depth_image_topic, cam_info_topic))
34  return false;
35 
36  sync_->registerCallback(boost::bind(&ClientROS::imageCallback, this, _1, _2));
37 
38  return true;
39 }
40 
41 // ----------------------------------------------------------------------------------------
42 
44 {
45  new_image_ = false;
46  image_ptr_ = &image;
47  cb_queue_.callAvailable();
48  return new_image_;
49 }
50 
51 // ----------------------------------------------------------------------------------------
52 
54 {
55  new_image_ = false;
56  image_ptr_ = nullptr;
57  cb_queue_.callAvailable();
58  if (!new_image_)
59  {
60  delete image_ptr_; // Needs to be deleted, because caller doesn't get a shared ptr to this raw pointer.
61  return nullptr;
62  }
63  return ImagePtr(image_ptr_);
64 }
65 
66 }
std::string
std::shared_ptr
rgbd::ClientROSBase::sync_
std::unique_ptr< message_filters::Synchronizer< RGBDApproxPolicy > > sync_
Definition: client_ros_base.h:75
rgbd::ClientROS::nextImage
ImagePtr nextImage()
Get a new Image. If no new image has been received since the last call, The ImagePtr will be a nullpt...
Definition: client_ros.cpp:53
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::ClientROS::ClientROS
ClientROS()
Constructor.
Definition: client_ros.cpp:17
rgbd
Definition: client.h:24
rgbd::ClientROS::~ClientROS
virtual ~ClientROS()
Destructor.
Definition: client_ros.cpp:23
rgbd::ClientROS::cb_queue_
ros::CallbackQueue cb_queue_
Definition: client_ros.h:71
image.h
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::ImagePtr
std::shared_ptr< Image > ImagePtr
Definition: types.h:8
rgbd::ClientROSBase
Client which subscribes to regular ROS image topics.
Definition: client_ros_base.h:32
client_ros.h
rgbd::ClientROSBase::new_image_
bool new_image_
new_image_ Track if image is updated in a callback.
Definition: client_ros_base.h:84
rgbd::ClientROS::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.cpp:29
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