Autoware.Auto
initialization.hpp
Go to the documentation of this file.
1 // Copyright 2019-2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 
18 #ifndef LOCALIZATION_COMMON__INITIALIZATION_HPP_
19 #define LOCALIZATION_COMMON__INITIALIZATION_HPP_
20 
22 #include <geometry_msgs/msg/transform.hpp>
25 #include <tf2/buffer_core.h>
26 #include <experimental/optional>
27 #include <string>
28 
29 // probably include the motion model
30 
31 namespace autoware
32 {
33 namespace localization
34 {
35 namespace localization_common
36 {
37 
41 template<typename Derived>
42 class LOCALIZATION_COMMON_PUBLIC PoseInitializerBase
43  : public common::helper_functions::crtp<Derived>
44 {
46 
47 public:
59  PoseT guess(
60  const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
61  const std::string & target_frame, const std::string & source_frame)
62  {
63  try {
64  // attempt to get transform at a given point.
65  return tf_graph.lookupTransform(target_frame, source_frame, time_point);
66  // TODO(yunus.caliskan): Consider detecting too large interpolations and issuing a
67  // warning/error.
68  } catch (const tf2::ExtrapolationException &) {
69  return this->impl().extrapolate(tf_graph, time_point, target_frame, source_frame);
70  } catch (...) {
71  if (!m_fallback_pose) {
72  std::rethrow_exception(std::current_exception());
73  }
74  if ((m_fallback_pose->header.frame_id != target_frame) ||
75  (m_fallback_pose->child_frame_id != source_frame))
76  {
77  throw std::runtime_error(
78  "The initial pose provided to the pose initializer does not "
79  "have the matching frame IDs.");
80  }
81  m_fallback_pose.value().header.stamp = ::time_utils::to_message(time_point);
82  return m_fallback_pose.value();
83  }
84  }
85 
90  void set_fallback_pose(const PoseT & pose)
91  {
92  m_fallback_pose.emplace(pose);
93  }
94 
95  PoseT get_fallback_pose(tf2::TimePoint time_point)
96  {
97  m_fallback_pose.value().header.stamp = ::time_utils::to_message(time_point);
98  return m_fallback_pose.value();
99  }
100 
101 private:
102  std::experimental::optional<PoseT> m_fallback_pose{std::experimental::nullopt};
103 };
104 
107 class LOCALIZATION_COMMON_PUBLIC BestEffortInitializer
108  : public PoseInitializerBase<BestEffortInitializer>
109 {
111 
112 public:
119  PoseT extrapolate(
120  const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
121  const std::string & target_frame, const std::string & source_frame);
122 };
123 
124 } // namespace localization_common
125 } // namespace localization
126 } // namespace autoware
127 
128 #endif // LOCALIZATION_COMMON__INITIALIZATION_HPP_
time_utils::to_message
TIME_UTILS_PUBLIC builtin_interfaces::msg::Time to_message(std::chrono::system_clock::time_point t)
Convert from std::chrono::time_point to time message.
Definition: time_utils.cpp:67
autoware::localization::localization_common::PoseInitializerBase::set_fallback_pose
void set_fallback_pose(const PoseT &pose)
Explicitly set a transform to be served first time a queried transform is not available....
Definition: initialization.hpp:90
autoware::localization::localization_common::PoseInitializerBase
Definition: initialization.hpp:42
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::helper_functions::crtp
Definition: crtp.hpp:29
motion::motion_testing_nodes::TransformStamped
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
crtp.hpp
This file includes common helper functions.
time_utils.hpp
autoware::localization::localization_common::PoseInitializerBase::guess
PoseT guess(const tf2::BufferCore &tf_graph, tf2::TimePoint time_point, const std::string &target_frame, const std::string &source_frame)
Definition: initialization.hpp:59
autoware::localization::localization_common::PoseInitializerBase::get_fallback_pose
PoseT get_fallback_pose(tf2::TimePoint time_point)
Definition: initialization.hpp:95
autoware::localization::localization_common::BestEffortInitializer
Definition: initialization.hpp:107
visibility_control.hpp