Apollo  v5.5.0
Open source self driving car software
transform_server.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 <map>
19 #include <set>
20 #include <string>
21 #include <vector>
22 
23 namespace apollo {
24 namespace perception {
25 namespace camera {
26 
27 struct Transform {
28  double timestamp;
29  double qw;
30  double qx;
31  double qy;
32  double qz;
33  double tx;
34  double ty;
35  double tz;
36 };
37 
39  public:
42 
43  inline const std::set<std::string> &vertices() { return vertices_; }
44 
45  bool Init(const std::vector<std::string> &camera_names,
46  const std::string &params_path);
47 
48  bool AddTransform(const std::string &child_frame_id,
49  const std::string &frame_id,
50  const Eigen::Affine3d &transform);
51 
52  bool QueryTransform(const std::string &child_frame_id,
53  const std::string &frame_id, Eigen::Affine3d *transform);
54 
55  void print();
56 
57  bool LoadFromFile(const std::string &tf_input, float frequency = 200.0f);
58 
59  bool QueryPos(double timestamp, Eigen::Affine3d *pose);
60 
61  private:
62  struct Edge {
63  std::string child_frame_id;
64  std::string frame_id;
65  Eigen::Affine3d transform;
66  };
67 
68  std::vector<Transform> tf_;
69 
70  double error_limit_ = 1.0;
71  // frame ids
72  std::set<std::string> vertices_;
73 
74  // multimap from child frame id to frame id
75  std::multimap<std::string, Edge> edges_;
76 
77  bool FindTransform(const std::string &child_frame_id,
78  const std::string &frame_id, Eigen::Affine3d *transform,
79  std::map<std::string, bool> *visited);
80 };
81 
82 } // namespace camera
83 } // namespace perception
84 } // namespace apollo
Definition: transform_server.h:27
Definition: blob.h:72
~TransformServer()
Definition: transform_server.h:41
const std::set< std::string > & vertices()
Definition: transform_server.h:43
double qx
Definition: transform_server.h:30
double tx
Definition: transform_server.h:33
double qz
Definition: transform_server.h:32
Definition: transform_server.h:38
double timestamp
Definition: transform_server.h:28
double qw
Definition: transform_server.h:29
TransformServer()
Definition: transform_server.h:40
double qy
Definition: transform_server.h:31
double ty
Definition: transform_server.h:34
double tz
Definition: transform_server.h:35