Apollo  6.0
Open source self driving car software
Public Member Functions | Static Public Member Functions | List of all members
apollo::localization::msf::OfflineLocalVisualizer Class Reference

Offline localization visualization tool. More...

#include <offline_local_visualizer.h>

Collaboration diagram for apollo::localization::msf::OfflineLocalVisualizer:
Collaboration graph

Public Member Functions

 OfflineLocalVisualizer ()
 
 ~OfflineLocalVisualizer ()
 
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)
 
void Visualize ()
 
bool GetZoneIdFromMapFolder (const std::string &map_folder, const unsigned int resolution_id, int *zone_id)
 

Static Public Member Functions

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)
 

Detailed Description

Offline localization visualization tool.

Constructor & Destructor Documentation

◆ OfflineLocalVisualizer()

apollo::localization::msf::OfflineLocalVisualizer::OfflineLocalVisualizer ( )

◆ ~OfflineLocalVisualizer()

apollo::localization::msf::OfflineLocalVisualizer::~OfflineLocalVisualizer ( )

Member Function Documentation

◆ GetZoneIdFromMapFolder()

bool apollo::localization::msf::OfflineLocalVisualizer::GetZoneIdFromMapFolder ( const std::string &  map_folder,
const unsigned int  resolution_id,
int *  zone_id 
)

◆ Init()

bool apollo::localization::msf::OfflineLocalVisualizer::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 
)

◆ PoseAndStdInterpolationByTime()

static void apollo::localization::msf::OfflineLocalVisualizer::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 
)
static

◆ Visualize()

void apollo::localization::msf::OfflineLocalVisualizer::Visualize ( )

The documentation for this class was generated from the following file: