#include <poses_interpolation.h>
|
| PosesInterpolation () |
|
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) |
|
void | DoInterpolation () |
|
◆ PosesInterpolation()
apollo::localization::msf::PosesInterpolation::PosesInterpolation |
( |
| ) |
|
◆ DoInterpolation()
void apollo::localization::msf::PosesInterpolation::DoInterpolation |
( |
| ) |
|
在文件 poses_interpolation.cc 第 46 行定义.
46 {
47
50 &input_poses_timestamps_);
51
52
53 LoadPCDTimestamp();
54
55
56 PoseInterpolationByTime(input_poses_, input_poses_timestamps_,
57 ref_timestamps_, ref_ids_, &out_indexes_,
58 &out_timestamps_, &out_poses_);
59
60
61 WritePCDPoses();
62}
EigenVector< Eigen::Vector3d > EigenVector3dVec
void LoadPosesAndStds(const std::string &file_path, ::apollo::common::EigenAffine3dVec *poses, ::apollo::common::EigenVector3dVec *stds, std::vector< double > *timestamps)
Load poses and stds their timestamps.
◆ Init()
bool apollo::localization::msf::PosesInterpolation::Init |
( |
const std::string & |
input_poses_path, |
|
|
const std::string & |
ref_timestamps_path, |
|
|
const std::string & |
out_poses_path, |
|
|
const std::string & |
extrinsic_path |
|
) |
| |
在文件 poses_interpolation.cc 第 28 行定义.
31 {
32 this->input_poses_path_ = input_poses_path;
33 this->ref_timestamps_path_ = ref_timestamps_path;
34 this->out_poses_path_ = out_poses_path;
35 this->extrinsic_path_ = extrinsic_path;
36
38 if (!success) {
39 AERROR <<
"Load lidar extrinsic failed.";
40 return false;
41 }
42
43 return true;
44}
bool LoadExtrinsic(const std::string &file_path, Eigen::Affine3d *extrinsic)
Load the velodyne extrinsic from a YAML file.
该类的文档由以下文件生成: