27 #include "Eigen/Geometry" 31 namespace localization {
37 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 const bool is_global =
false);
59 std::vector<unsigned char>*
intensities,
bool is_global =
false);
64 std::vector<double>* timestamps);
69 std::vector<double>* timestamps,
70 std::vector<unsigned int>* pcd_indices);
76 std::vector<double>* timestamps);
EigenVector< Eigen::Affine3d > EigenAffine3dVec
Definition: eigen_defs.h:39
Definition: velodyne_utility.h:36
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.
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
EIGEN_MAKE_ALIGNED_OPERATOR_NEW unsigned int frame_index
The frame index.
Definition: velodyne_utility.h:39
double timestamp
The time stamp.
Definition: velodyne_utility.h:41
std::vector< unsigned char > laser_ids
The laser IDs.
Definition: velodyne_utility.h:47
bool LoadExtrinsic(const std::string &file_path, Eigen::Affine3d *extrinsic)
Save the PCD poses with their timestamps.
void LoadPcdPoses(const std::string &file_path, ::apollo::common::EigenAffine3dVec *poses, std::vector< double > *timestamps)
Load the PCD poses with their timestamps.
::apollo::common::EigenVector3dVec pt3ds
The 3D point cloud in this frame.
Definition: velodyne_utility.h:43
EigenVector< Eigen::Vector3d > EigenVector3dVec
Definition: eigen_defs.h:38
void LoadPcds(const std::string &file_path, const unsigned int frame_index, const Eigen::Affine3d &pose, VelodyneFrame *velodyne_frame, const bool is_global=false)
Eigen::Affine3d pose
The pose of the frame.
Definition: velodyne_utility.h:49
std::vector< unsigned char > intensities
The laser reflection values in this frames.
Definition: velodyne_utility.h:45
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34