21#include "Eigen/Geometry"
22#include "Eigen/StdVector"
25namespace localization {
29 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
37 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 void UpdateLidarPose(
double timestamp,
const Eigen::Affine3d& locator_pose,
44 const Eigen::Affine3d& novatel_pose);
49 const Eigen::Affine3d& novatel_pose);
56 static const unsigned int s_buffer_size_;
60 Eigen::aligned_allocator<LocalizationStampedPosePair>>
62 unsigned int used_buffer_size_;
63 unsigned int head_index_;
64 bool has_initialized_;
unsigned int GetHeadIndex()
Get the current head of the buffer
unsigned int GetUsedBufferSize()
Get the used size of buffer
Eigen::Affine3d UpdateOdometryPose(double timestamp, const Eigen::Affine3d &novatel_pose)
receive an odometry pose and estimate the output pose according to last lidar pose recorded.
void UpdateLidarPose(double timestamp, const Eigen::Affine3d &locator_pose, const Eigen::Affine3d &novatel_pose)
receive a pair of lidar pose and odometry pose which almost have the same timestame
~LocalizationPoseBuffer()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LocalizationPoseBuffer()
Eigen::Affine3d locator_pose
Eigen::Affine3d novatel_pose
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double timestamp