diff --git a/ed_sensor_integration/CMakeLists.txt b/ed_sensor_integration/CMakeLists.txt index 8483906c..7362f2e5 100644 --- a/ed_sensor_integration/CMakeLists.txt +++ b/ed_sensor_integration/CMakeLists.txt @@ -5,9 +5,9 @@ find_package(catkin REQUIRED COMPONENTS ed ed_sensor_integration_msgs geolib2 + geometry_msgs image_geometry sensor_msgs - tf2 tf2_ros tue_config tue_filesystem diff --git a/ed_sensor_integration/include/ed/kinect/image_buffer.h b/ed_sensor_integration/include/ed/kinect/image_buffer.h index ba905abb..92a3dc44 100644 --- a/ed_sensor_integration/include/ed/kinect/image_buffer.h +++ b/ed_sensor_integration/include/ed/kinect/image_buffer.h @@ -2,9 +2,13 @@ #define ED_SENSOR_INTEGRATION_IMAGE_BUFFER_H_ #include -#include + #include +#include + +#include + #include #include #include @@ -15,7 +19,7 @@ namespace rgbd class Client; } -namespace tf +namespace tf2_ros { class TransformListener; } @@ -66,7 +70,8 @@ class ImageBuffer std::unique_ptr rgbd_client_; - std::unique_ptr tf_listener_; + tf2_ros::Buffer tf_buffer_; + std::unique_ptr tf_listener_; /** * @brief Newer images should be pushed on the front. This will result in the front being the most recent and the back being the oldest diff --git a/ed_sensor_integration/package.xml b/ed_sensor_integration/package.xml index d256900b..ae842d1f 100644 --- a/ed_sensor_integration/package.xml +++ b/ed_sensor_integration/package.xml @@ -16,9 +16,9 @@ ed ed_sensor_integration_msgs geolib2 + geometry_msgs image_geometry sensor_msgs - tf2 tf2_ros tue_config tue_filesystem diff --git a/ed_sensor_integration/src/kinect/image_buffer.cpp b/ed_sensor_integration/src/kinect/image_buffer.cpp index 1b4d27e7..d0fe6ad2 100644 --- a/ed_sensor_integration/src/kinect/image_buffer.cpp +++ b/ed_sensor_integration/src/kinect/image_buffer.cpp @@ -1,13 +1,17 @@ #include "ed/kinect/image_buffer.h" +#include + +#include + #include #include -#include -#include + +#include // ---------------------------------------------------------------------------------------------------- -ImageBuffer::ImageBuffer() : rgbd_client_(nullptr), tf_listener_(nullptr), shutdown_(false) +ImageBuffer::ImageBuffer() : rgbd_client_(nullptr), tf_buffer_(), tf_listener_(nullptr), shutdown_(false) { } @@ -32,7 +36,7 @@ void ImageBuffer::initialize(const std::string& topic, const std::string& root_f rgbd_client_->initialize(topic); if (!tf_listener_) - tf_listener_ = std::make_unique(); + tf_listener_ = std::make_unique(tf_buffer_); worker_thread_ptr_ = std::make_unique(&ImageBuffer::workerThreadFunc, this, worker_thread_frequency); } @@ -70,8 +74,8 @@ bool ImageBuffer::waitForRecentImage(rgbd::ImageConstPtr& image, geo::Pose3D& se // - - - - - - - - - - - - - - - - - - // Wait until we have a tf - if (!tf_listener_->canTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp()))) // Get the TF when it is available now - if (!tf_listener_->waitForTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp()), t_end - ros::Time::now())) + if (!tf_buffer_.canTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp()))) // Get the TF when it is available now + if (!tf_buffer_.canTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp()), t_end - ros::Time::now())) return false; // - - - - - - - - - - - - - - - - - - @@ -79,11 +83,10 @@ bool ImageBuffer::waitForRecentImage(rgbd::ImageConstPtr& image, geo::Pose3D& se try { - tf::StampedTransform t_sensor_pose; - tf_listener_->lookupTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp()), t_sensor_pose); - geo::convert(t_sensor_pose, sensor_pose); + geometry_msgs::TransformStamped t_sensor_pose = tf_buffer_.lookupTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp())); + geo::convert(t_sensor_pose.transform, sensor_pose); } - catch(tf::TransformException& ex) + catch(tf2::TransformException& ex) { ROS_ERROR_NAMED("image_buffer", "[IMAGE_BUFFER] Could not get sensor pose: %s", ex.what()); return false; @@ -149,20 +152,18 @@ bool ImageBuffer::getMostRecentImageTF() rgbd::ImageConstPtr& rgbd_image = *it; try { - tf::StampedTransform t_sensor_pose; - tf_listener_->lookupTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp()), t_sensor_pose); - geo::convert(t_sensor_pose, sensor_pose); + geometry_msgs::TransformStamped t_sensor_pose = tf_buffer_.lookupTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(rgbd_image->getTimestamp())); + geo::convert(t_sensor_pose.transform, sensor_pose); } - catch (tf::ExtrapolationException& ex) + catch (tf2::ExtrapolationException& ex) { try { // Now we have to check if the error was an interpolation or extrapolation error (i.e., the image is too old or // to new, respectively). If it is too old, discard it. - tf::StampedTransform latest_sensor_pose; - tf_listener_->lookupTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(0), latest_sensor_pose); + geometry_msgs::TransformStamped latest_sensor_pose = tf_buffer_.lookupTransform(root_frame_, rgbd_image->getFrameId(), ros::Time(0)); // If image time stamp is older than latest transform, the image is too old and the tf data is not available anymore - if ( latest_sensor_pose.stamp_ > ros::Time(rgbd_image->getTimestamp()) ) + if ( latest_sensor_pose.header.stamp > ros::Time(rgbd_image->getTimestamp()) ) { 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() continue; } } - catch (tf::TransformException& ex) + catch (tf2::TransformException& ex) { 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()); ROS_WARN_NAMED("image_buffer", "[IMAGE_BUFFER] Could not get latest sensor pose (probably because tf is still initializing): %s", ex.what()); continue; } } - catch (tf::TransformException& ex) + catch (tf2::TransformException& ex) { ROS_ERROR_DELAYED_THROTTLE_NAMED(10, "image_buffer", "[IMAGE_BUFFER] Could not get sensor pose: %s", ex.what()); ROS_WARN_NAMED("image_buffer", "[IMAGE_BUFFER] Could not get sensor pose: %s", ex.what()); diff --git a/ed_sensor_integration/src/laser/laser_plugin.cpp b/ed_sensor_integration/src/laser/laser_plugin.cpp index aed11d15..7a28f595 100644 --- a/ed_sensor_integration/src/laser/laser_plugin.cpp +++ b/ed_sensor_integration/src/laser/laser_plugin.cpp @@ -12,12 +12,14 @@ #include #include +#include + #include #include #include -#include "tf2/transform_datatypes.h" +#include #include diff --git a/ed_sensor_integration/src/laser/laser_plugin.h b/ed_sensor_integration/src/laser/laser_plugin.h index dc44e972..83bbd933 100644 --- a/ed_sensor_integration/src/laser/laser_plugin.h +++ b/ed_sensor_integration/src/laser/laser_plugin.h @@ -11,13 +11,17 @@ #include #include #include -#include #include #include #include #include +namespace tf2_ros +{ +class TransformListener; +} + class LaserPlugin : public ed::Plugin {