18 #ifndef LOCALIZATION_COMMON__INITIALIZATION_HPP_ 19 #define LOCALIZATION_COMMON__INITIALIZATION_HPP_ 22 #include <geometry_msgs/msg/transform.hpp> 24 #include <tf2/buffer_core.h> 30 namespace localization
32 namespace localization_common
38 template<
typename Derived>
55 const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
56 const std::string & target_frame,
const std::string & source_frame)
62 ret = tf_graph.lookupTransform(target_frame, source_frame, time_point);
65 }
catch (
const tf2::ExtrapolationException &) {
66 ret = this->impl().extrapolate(tf_graph, time_point, target_frame, source_frame);
88 const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
89 const std::string & target_frame,
const std::string & source_frame);
96 #endif // LOCALIZATION_COMMON__INITIALIZATION_HPP_
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
Definition: initialization.hpp:75
This file includes common helper functions.
PoseT guess(const tf2::BufferCore &tf_graph, tf2::TimePoint time_point, const std::string &target_frame, const std::string &source_frame)
Definition: initialization.hpp:54
Definition: initialization.hpp:39
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24