32 namespace localization {
40 #define LOC_INFO_NUM 3 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);
56 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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);
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);
79 const unsigned int resolution_id,
int *zone_id);
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_;
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_;
99 pyramid_map::BaseMapConfig map_config_;
100 unsigned int resolution_id_;
104 VisualizationEngine visual_engine_;
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)
~OfflineLocalVisualizer()
EigenVector< Eigen::Vector3d > EigenVector3dVec
Definition: eigen_defs.h:38
The engine for localization visualization.
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34