Apollo  6.0
Open source self driving car software
offline_local_visualizer.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 
21 #pragma once
22 
23 #include <map>
24 #include <string>
25 #include <vector>
26 
30 
31 namespace apollo {
32 namespace localization {
33 namespace msf {
34 
40 #define LOC_INFO_NUM 3
41 
42  public:
45 
46  public:
47  bool Init(const std::string &map_folder, const std::string &map_visual_folder,
48  const std::string &pcd_folder,
49  const std::string &pcd_timestamp_file,
50  const std::string &gnss_loc_file, const std::string &lidar_loc_file,
51  const std::string &fusion_loc_file,
52  const std::string &extrinsic_file);
53 
54  void Visualize();
55 
56  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
57 
58  private:
59  bool PCDTimestampFileHandler();
60  bool LidarLocFileHandler(const std::vector<double> &pcd_timestamps);
61  bool GnssLocFileHandler(const std::vector<double> &pcd_timestamps);
62  bool FusionLocFileHandler(const std::vector<double> &pcd_timestamps);
63 
64  // void PoseInterpolationByTime(
65  // const ::apollo::common::EigenAffine3dVec &in_poses,
66  // const std::vector<double> &in_timestamps,
67  // const std::vector<double> &ref_timestamps,
68  // std::map<unsigned int, Eigen::Affine3d> &out_poses);
69  public:
73  const std::vector<double> &in_timestamps,
74  const std::vector<double> &ref_timestamps,
75  std::map<unsigned int, Eigen::Affine3d> *out_poses,
76  std::map<unsigned int, Eigen::Vector3d> *out_stds);
77 
78  bool GetZoneIdFromMapFolder(const std::string &map_folder,
79  const unsigned int resolution_id, int *zone_id);
80 
81  private:
82  std::string map_folder_;
83  std::string map_visual_folder_;
84  std::string pcd_folder_;
85  std::string pcd_timestamp_file_;
86  std::string gnss_loc_file_;
87  std::string lidar_loc_file_;
88  std::string fusion_loc_file_;
89  std::string extrinsic_file_;
90 
91  std::vector<double> pcd_timestamps_;
92  std::map<unsigned int, Eigen::Affine3d> gnss_poses_;
93  std::map<unsigned int, Eigen::Vector3d> gnss_stds_;
94  std::map<unsigned int, Eigen::Affine3d> lidar_poses_;
95  std::map<unsigned int, Eigen::Vector3d> lidar_stds_;
96  std::map<unsigned int, Eigen::Affine3d> fusion_poses_;
97  std::map<unsigned int, Eigen::Vector3d> fusion_stds_;
98 
99  pyramid_map::BaseMapConfig map_config_;
100  unsigned int resolution_id_;
101  int zone_id_;
102 
103  Eigen::Affine3d velodyne_extrinsic_;
104  VisualizationEngine visual_engine_;
105 };
106 
107 } // namespace msf
108 } // namespace localization
109 } // namespace apollo
Offline localization visualization tool.
Definition: offline_local_visualizer.h:39
bool GetZoneIdFromMapFolder(const std::string &map_folder, const unsigned int resolution_id, int *zone_id)
EigenVector< Eigen::Affine3d > EigenAffine3dVec
Definition: eigen_defs.h:39
bool Init(const std::string &map_folder, const std::string &map_visual_folder, const std::string &pcd_folder, const std::string &pcd_timestamp_file, const std::string &gnss_loc_file, const std::string &lidar_loc_file, const std::string &fusion_loc_file, const std::string &extrinsic_file)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
static void PoseAndStdInterpolationByTime(const ::apollo::common::EigenAffine3dVec &in_poses, const ::apollo::common::EigenVector3dVec &in_stds, const std::vector< double > &in_timestamps, const std::vector< double > &ref_timestamps, std::map< unsigned int, Eigen::Affine3d > *out_poses, std::map< unsigned int, Eigen::Vector3d > *out_stds)
EigenVector< Eigen::Vector3d > EigenVector3dVec
Definition: eigen_defs.h:38
The engine for localization visualization.
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34