Apollo  6.0
Open source self driving car software
poses_interpolation.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2017 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 
22 #pragma once
23 
24 #include <iostream>
25 #include <string>
26 #include <vector>
27 
29 
34 namespace apollo {
35 namespace localization {
36 namespace msf {
37 
39  public:
41  bool Init(const std::string &input_poses_path,
42  const std::string &ref_timestamps_path,
43  const std::string &out_poses_path,
44  const std::string &extrinsic_path);
45  void DoInterpolation();
46 
47  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48 
49  private:
50  void LoadPCDTimestamp();
51  void WritePCDPoses();
52  void PoseInterpolationByTime(
54  const std::vector<double> &in_timestamps,
55  const std::vector<double> &ref_timestamps,
56  const std::vector<unsigned int> &ref_indexes,
57  std::vector<unsigned int> *out_indexes,
58  std::vector<double> *out_timestamps,
60 
61  private:
62  std::string input_poses_path_;
63  std::string ref_timestamps_path_;
64  std::string out_poses_path_;
65  std::string extrinsic_path_;
66 
67  Eigen::Affine3d velodyne_extrinsic_;
68 
70  std::vector<double> input_poses_timestamps_;
71 
72  std::vector<double> ref_timestamps_;
73  std::vector<unsigned int> ref_ids_;
74 
75  std::vector<unsigned int> out_indexes_;
76  std::vector<double> out_timestamps_;
78 };
79 
80 } // namespace msf
81 } // namespace localization
82 } // namespace apollo
EigenVector< Eigen::Affine3d > EigenAffine3dVec
Definition: eigen_defs.h:39
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool Init(const std::string &input_poses_path, const std::string &ref_timestamps_path, const std::string &out_poses_path, const std::string &extrinsic_path)
Definition: poses_interpolation.h:38
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34