@@ -28,6 +28,7 @@ void ImageBuffer::initialize(const std::string& topic, const std::string& root_f
2828
2929 if (!kinect_client_)
3030 kinect_client_ = std::make_unique<rgbd::Client>();
31+
3132 kinect_client_->initialize (topic);
3233
3334 if (!tf_listener_)
@@ -41,7 +42,10 @@ void ImageBuffer::initialize(const std::string& topic, const std::string& root_f
4142bool ImageBuffer::waitForRecentImage (rgbd::ImageConstPtr& image, geo::Pose3D& sensor_pose, double timeout_sec)
4243{
4344 if (!kinect_client_)
45+ {
46+ ROS_ERROR (" [IMAGE_BUFFER] No RGBD client" );
4447 return false ;
48+ }
4549
4650 // - - - - - - - - - - - - - - - - - -
4751 // Wait until we get a new image
@@ -97,7 +101,10 @@ bool ImageBuffer::nextImage(rgbd::ImageConstPtr& image, geo::Pose3D& sensor_pose
97101{
98102 std::lock_guard<std::mutex> lg (recent_image_mutex_);
99103 if (!recent_image_.first )
104+ {
105+ ROS_DEBUG (" [IMAGE_BUFFER] No new image" );
100106 return false ;
107+ }
101108
102109 image = recent_image_.first ;
103110 sensor_pose = recent_image_.second ;
@@ -112,14 +119,20 @@ bool ImageBuffer::nextImage(rgbd::ImageConstPtr& image, geo::Pose3D& sensor_pose
112119bool ImageBuffer::getMostRecentImageTF ()
113120{
114121 if (!kinect_client_)
122+ {
123+ ROS_ERROR (" [IMAGE_BUFFER] No RGBD client" );
115124 return false ;
125+ }
116126
117127 // - - - - - - - - - - - - - - - - - -
118128 // Fetch kinect image and place in image buffer
119129
120130 rgbd::ImageConstPtr rgbd_image = kinect_client_->nextImage ();
121131 if (!rgbd_image)
132+ {
133+ ROS_DEBUG (" [IMAGE_BUFFER] No new image from the RGBD client" );
122134 return false ;
135+ }
123136
124137 geo::Pose3D sensor_pose;
125138
0 commit comments