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>
24 #include <tf2/buffer_core.h>
25 #include <string>
26 // probably include the motion model
27 
28 namespace autoware
29 {
30 namespace localization
31 {
32 namespace localization_common
33 {
34 
38 template<typename Derived>
39 class LOCALIZATION_COMMON_PUBLIC PoseInitializerBase
40  : public common::helper_functions::crtp<Derived>
41 {
43 
44 public:
54  PoseT guess(
55  const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
56  const std::string & target_frame, const std::string & source_frame)
57  {
58  PoseT ret;
59 
60  try {
61  // attempt to get transform at a given point.
62  ret = tf_graph.lookupTransform(target_frame, source_frame, time_point);
63  // TODO(yunus.caliskan): Consider detecting too large interpolations and issuing a
64  // warning/error.
65  } catch (const tf2::ExtrapolationException &) {
66  ret = this->impl().extrapolate(tf_graph, time_point, target_frame, source_frame);
67  }
68 
69  return ret;
70  }
71 };
72 
75 class LOCALIZATION_COMMON_PUBLIC BestEffortInitializer
76  : public PoseInitializerBase<BestEffortInitializer>
77 {
79 
80 public:
87  PoseT extrapolate(
88  const tf2::BufferCore & tf_graph, tf2::TimePoint time_point,
89  const std::string & target_frame, const std::string & source_frame);
90 };
91 
92 } // namespace localization_common
93 } // namespace localization
94 } // namespace autoware
95 
96 #endif // LOCALIZATION_COMMON__INITIALIZATION_HPP_
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
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
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24