18 #ifndef LOCALIZATION_COMMON__INITIALIZATION_HPP_
19 #define LOCALIZATION_COMMON__INITIALIZATION_HPP_
22 #include <geometry_msgs/msg/transform.hpp>
25 #include <tf2/buffer_core.h>
26 #include <experimental/optional>
33 namespace localization
35 namespace localization_common
41 template<
typename Derived>
60 const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
61 const std::string & target_frame,
const std::string & source_frame)
65 return tf_graph.lookupTransform(target_frame, source_frame, time_point);
68 }
catch (
const tf2::ExtrapolationException &) {
69 return this->impl().extrapolate(tf_graph, time_point, target_frame, source_frame);
71 if (!m_fallback_pose) {
72 std::rethrow_exception(std::current_exception());
74 if ((m_fallback_pose->header.frame_id != target_frame) ||
75 (m_fallback_pose->child_frame_id != source_frame))
77 throw std::runtime_error(
78 "The initial pose provided to the pose initializer does not "
79 "have the matching frame IDs.");
82 return m_fallback_pose.value();
92 m_fallback_pose.emplace(pose);
98 return m_fallback_pose.value();
102 std::experimental::optional<PoseT> m_fallback_pose{std::experimental::nullopt};
120 const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
121 const std::string & target_frame,
const std::string & source_frame);
128 #endif // LOCALIZATION_COMMON__INITIALIZATION_HPP_