|
15 | 15 | #ifndef AUTOWARE_UTILS_PCL__MANAGED_TRANSFORM_BUFFER_HPP_
|
16 | 16 | #define AUTOWARE_UTILS_PCL__MANAGED_TRANSFORM_BUFFER_HPP_
|
17 | 17 |
|
18 |
| -#include <autoware_utils_geometry/transform_listener.hpp> |
| 18 | +#include <autoware_utils_tf/transform_listener.hpp> |
19 | 19 | #include <eigen3/Eigen/Core>
|
20 | 20 | #include <pcl_ros/transforms.hpp>
|
21 | 21 | #include <rclcpp/rclcpp.hpp>
|
@@ -73,7 +73,7 @@ class ManagedTransformBuffer
|
73 | 73 | return get_static_transform(target_frame, source_frame, eigen_transform);
|
74 | 74 | };
|
75 | 75 | } else {
|
76 |
| - tf_listener_ = std::make_unique<autoware_utils_geometry::TransformListener>(node); |
| 76 | + tf_listener_ = std::make_unique<autoware_utils_tf::TransformListener>(node); |
77 | 77 | get_transform_ = [this](
|
78 | 78 | const std::string & target_frame, const std::string & source_frame,
|
79 | 79 | Eigen::Matrix4f & eigen_transform) {
|
@@ -173,7 +173,7 @@ class ManagedTransformBuffer
|
173 | 173 | }
|
174 | 174 |
|
175 | 175 | // Get the transform from the TF tree
|
176 |
| - tf_listener_ = std::make_unique<autoware_utils_geometry::TransformListener>(node_); |
| 176 | + tf_listener_ = std::make_unique<autoware_utils_tf::TransformListener>(node_); |
177 | 177 | auto tf = tf_listener_->get_transform(
|
178 | 178 | target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms));
|
179 | 179 | tf_listener_.reset();
|
@@ -218,7 +218,7 @@ class ManagedTransformBuffer
|
218 | 218 |
|
219 | 219 | TFMap buffer_;
|
220 | 220 | rclcpp::Node * const node_;
|
221 |
| - std::unique_ptr<autoware_utils_geometry::TransformListener> tf_listener_; |
| 221 | + std::unique_ptr<autoware_utils_tf::TransformListener> tf_listener_; |
222 | 222 | std::function<bool(const std::string &, const std::string &, Eigen::Matrix4f &)> get_transform_;
|
223 | 223 | };
|
224 | 224 |
|
|
0 commit comments