11#include " ed/kinect/image_buffer.h"
22
3+ #include < geolib/ros/msg_conversions.h>
4+
5+ #include < geometry_msgs/TransformStamped.h>
6+
37#include < rgbd/client.h>
48#include < rgbd/image.h>
5- # include < tf/transform_listener.h >
6- #include < geolib/ros/tf_conversions .h>
9+
10+ #include < tf2_ros/transform_listener .h>
711
812// ----------------------------------------------------------------------------------------------------
913
10- ImageBuffer::ImageBuffer () : rgbd_client_(nullptr ), tf_listener_(nullptr ), shutdown_(false )
14+ ImageBuffer::ImageBuffer () : rgbd_client_(nullptr ), tf_buffer_(), tf_listener_(nullptr ), shutdown_(false )
1115{
1216}
1317
@@ -32,7 +36,7 @@ void ImageBuffer::initialize(const std::string& topic, const std::string& root_f
3236 rgbd_client_->initialize (topic);
3337
3438 if (!tf_listener_)
35- tf_listener_ = std::make_unique<tf ::TransformListener>();
39+ tf_listener_ = std::make_unique<tf2_ros ::TransformListener>(tf_buffer_ );
3640
3741 worker_thread_ptr_ = std::make_unique<std::thread>(&ImageBuffer::workerThreadFunc, this , worker_thread_frequency);
3842}
@@ -70,20 +74,19 @@ bool ImageBuffer::waitForRecentImage(rgbd::ImageConstPtr& image, geo::Pose3D& se
7074
7175 // - - - - - - - - - - - - - - - - - -
7276 // Wait until we have a tf
73- if (!tf_listener_-> canTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()))) // Get the TF when it is available now
74- if (!tf_listener_-> waitForTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()), t_end - ros::Time::now ()))
77+ if (!tf_buffer_. canTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()))) // Get the TF when it is available now
78+ if (!tf_buffer_. canTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()), t_end - ros::Time::now ()))
7579 return false ;
7680
7781 // - - - - - - - - - - - - - - - - - -
7882 // Calculate tf
7983
8084 try
8185 {
82- tf::StampedTransform t_sensor_pose;
83- tf_listener_->lookupTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()), t_sensor_pose);
84- geo::convert (t_sensor_pose, sensor_pose);
86+ geometry_msgs::TransformStamped t_sensor_pose = tf_buffer_.lookupTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()));
87+ geo::convert (t_sensor_pose.transform , sensor_pose);
8588 }
86- catch (tf ::TransformException& ex)
89+ catch (tf2 ::TransformException& ex)
8790 {
8891 ROS_ERROR_NAMED (" image_buffer" , " [IMAGE_BUFFER] Could not get sensor pose: %s" , ex.what ());
8992 return false ;
@@ -149,20 +152,18 @@ bool ImageBuffer::getMostRecentImageTF()
149152 rgbd::ImageConstPtr& rgbd_image = *it;
150153 try
151154 {
152- tf::StampedTransform t_sensor_pose;
153- tf_listener_->lookupTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()), t_sensor_pose);
154- geo::convert (t_sensor_pose, sensor_pose);
155+ geometry_msgs::TransformStamped t_sensor_pose = tf_buffer_.lookupTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (rgbd_image->getTimestamp ()));
156+ geo::convert (t_sensor_pose.transform , sensor_pose);
155157 }
156- catch (tf ::ExtrapolationException& ex)
158+ catch (tf2 ::ExtrapolationException& ex)
157159 {
158160 try
159161 {
160162 // Now we have to check if the error was an interpolation or extrapolation error (i.e., the image is too old or
161163 // to new, respectively). If it is too old, discard it.
162- tf::StampedTransform latest_sensor_pose;
163- tf_listener_->lookupTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (0 ), latest_sensor_pose);
164+ geometry_msgs::TransformStamped latest_sensor_pose = tf_buffer_.lookupTransform (root_frame_, rgbd_image->getFrameId (), ros::Time (0 ));
164165 // If image time stamp is older than latest transform, the image is too old and the tf data is not available anymore
165- if ( latest_sensor_pose.stamp_ > ros::Time (rgbd_image->getTimestamp ()) )
166+ if ( latest_sensor_pose.header . stamp > ros::Time (rgbd_image->getTimestamp ()) )
166167 {
167168
168169 ROS_DEBUG_STREAM_NAMED (" image_buffer" , " [IMAGE_BUFFER] Image too old to look-up tf. Deleting all images older than timestamp: " << std::fixed
@@ -178,14 +179,14 @@ bool ImageBuffer::getMostRecentImageTF()
178179 continue ;
179180 }
180181 }
181- catch (tf ::TransformException& ex)
182+ catch (tf2 ::TransformException& ex)
182183 {
183184 ROS_ERROR_DELAYED_THROTTLE_NAMED (10 , " image_buffer" , " [IMAGE_BUFFER] Could not get latest sensor pose (probably because tf is still initializing): %s" , ex.what ());
184185 ROS_WARN_NAMED (" image_buffer" , " [IMAGE_BUFFER] Could not get latest sensor pose (probably because tf is still initializing): %s" , ex.what ());
185186 continue ;
186187 }
187188 }
188- catch (tf ::TransformException& ex)
189+ catch (tf2 ::TransformException& ex)
189190 {
190191 ROS_ERROR_DELAYED_THROTTLE_NAMED (10 , " image_buffer" , " [IMAGE_BUFFER] Could not get sensor pose: %s" , ex.what ());
191192 ROS_WARN_NAMED (" image_buffer" , " [IMAGE_BUFFER] Could not get sensor pose: %s" , ex.what ());
0 commit comments