Apollo  6.0
Open source self driving car software
transform_wrapper.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <deque>
19 #include <memory>
20 #include <string>
21 
22 #include "Eigen/Core"
23 #include "Eigen/Dense"
24 #include "gflags/gflags.h"
25 
27 
28 namespace apollo {
29 namespace perception {
30 namespace onboard {
31 
33 
34 DECLARE_string(obs_sensor2novatel_tf2_frame_id);
35 DECLARE_string(obs_novatel2world_tf2_frame_id);
36 DECLARE_string(obs_novatel2world_tf2_child_frame_id);
37 DECLARE_double(obs_tf2_buff_size);
38 
40  double timestamp = 0.0; // in second
41  Eigen::Translation3d translation;
42  Eigen::Quaterniond rotation;
43 };
44 
46  public:
47  TransformCache() = default;
48  ~TransformCache() = default;
49 
50  void AddTransform(const StampedTransform& transform);
51  bool QueryTransform(double timestamp, StampedTransform* transform,
52  double max_duration = 0.0);
53 
54  inline void SetCacheDuration(double duration) { cache_duration_ = duration; }
55 
56  protected:
57  // in ascending order of time
58  std::deque<StampedTransform> transforms_;
59  double cache_duration_ = 1.0;
60 };
61 
63  public:
65  ~TransformWrapper() = default;
66 
67  void Init(const std::string& sensor2novatel_tf2_child_frame_id);
68  void Init(const std::string& sensor2novatel_tf2_frame_id,
69  const std::string& sensor2novatel_tf2_child_frame_id,
70  const std::string& novatel2world_tf2_frame_id,
71  const std::string& novatel2world_tf2_child_frame_id);
72 
73  // Attention: must initialize TransformWrapper first
74  bool GetSensor2worldTrans(double timestamp,
75  Eigen::Affine3d* sensor2world_trans,
76  Eigen::Affine3d* novatel2world_trans = nullptr);
77 
78  bool GetExtrinsics(Eigen::Affine3d* trans);
79 
80  // Attention: can be called without initlization
81  bool GetTrans(double timestamp, Eigen::Affine3d* trans,
82  const std::string& frame_id, const std::string& child_frame_id);
83 
84  bool GetExtrinsicsBySensorId(const std::string& from_sensor_id,
85  const std::string& to_sensor_id,
86  Eigen::Affine3d* trans);
87 
88  protected:
89  bool QueryTrans(double timestamp, StampedTransform* trans,
90  const std::string& frame_id,
91  const std::string& child_frame_id);
92 
93  private:
94  bool inited_ = false;
95 
96  Buffer* tf2_buffer_ = Buffer::Instance();
97 
98  std::string sensor2novatel_tf2_frame_id_;
99  std::string sensor2novatel_tf2_child_frame_id_;
100  std::string novatel2world_tf2_frame_id_;
101  std::string novatel2world_tf2_child_frame_id_;
102 
103  std::unique_ptr<Eigen::Affine3d> sensor2novatel_extrinsics_;
104 
105  TransformCache transform_cache_;
106 };
107 
108 } // namespace onboard
109 } // namespace perception
110 } // namespace apollo
Eigen::Quaterniond rotation
Definition: transform_wrapper.h:42
double timestamp
Definition: transform_wrapper.h:40
TransformWrapper()
Definition: transform_wrapper.h:64
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::deque< StampedTransform > transforms_
Definition: transform_wrapper.h:58
Definition: transform_wrapper.h:62
Definition: transform_wrapper.h:45
Definition: transform_wrapper.h:39
DECLARE_double(obs_buffer_match_precision)
DECLARE_string(obs_screen_output_dir)
bool Init(const char *binary_name)
Definition: buffer.h:33
void SetCacheDuration(double duration)
Definition: transform_wrapper.h:54
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
Eigen::Translation3d translation
Definition: transform_wrapper.h:41