35 namespace localization {
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);
47 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 void LoadPCDTimestamp();
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,
62 std::string input_poses_path_;
63 std::string ref_timestamps_path_;
64 std::string out_poses_path_;
65 std::string extrinsic_path_;
70 std::vector<double> input_poses_timestamps_;
72 std::vector<double> ref_timestamps_;
73 std::vector<unsigned int> ref_ids_;
75 std::vector<unsigned int> out_indexes_;
76 std::vector<double> out_timestamps_;
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