23#include "localization_msf/lidar_locator.h"
33namespace localization {
91 bool Init(
const std::string& map_path,
const unsigned int search_range_x,
92 const unsigned int search_range_y,
const int zone_id,
93 const unsigned int resolution_id = 0);
109 int Update(
const unsigned int frame_idx,
const Eigen::Affine3d& pose,
110 const Eigen::Vector3d velocity,
const LidarFrame& lidar_frame,
111 bool use_avx =
false);
113 void GetResult(Eigen::Affine3d* location, Eigen::Matrix3d* covariance,
114 double* location_score);
118 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
double vehicle_lidar_height_
void SetLocalizationMode(int mode)
apollo::localization::msf::pyramid_map::FloatMatrix FloatMatrix
apollo::localization::msf::pyramid_map::UIntMatrix UIntMatrix
double pre_vehicle_ground_height_
apollo::localization::msf::pyramid_map::PyramidMapMatrix PyramidMapMatrix
unsigned int resolution_id_
int Update(const unsigned int frame_idx, const Eigen::Affine3d &pose, const Eigen::Vector3d velocity, const LidarFrame &lidar_frame, bool use_avx=false)
void SetDeltaYawLimit(double limit)
Eigen::Vector2d map_left_top_corner_
apollo::localization::msf::pyramid_map::MapNodeIndex MapNodeIndex
void SetImageAlignMode(int mode)
bool Init(const std::string &map_path, const unsigned int search_range_x, const unsigned int search_range_y, const int zone_id, const unsigned int resolution_id=0)
void GetResult(Eigen::Affine3d *location, Eigen::Matrix3d *covariance, double *location_score)
void ComposeMapNode(const Eigen::Vector3d &trans)
PyramidMapNodePool map_node_pool_
void SetVehicleHeight(double height)
MapNodeData * lidar_map_node_
Eigen::Affine3d velodyne_extrinsic_
bool is_pre_ground_height_valid_
void GetLocalizationDistribution(Eigen::MatrixXd *distribution)
~LocalizationLidar()
The deconstructor.
void SetDeltaPitchRollLimit(double limit)
apollo::localization::msf::pyramid_map::PyramidMapNodePool PyramidMapNodePool
void SetValidThreshold(float valid_threashold)
apollo::localization::msf::pyramid_map::PyramidMap PyramidMap
void SetVelodyneExtrinsic(const Eigen::Affine3d &pose)
void RefineAltitudeFromMap(Eigen::Affine3d *pose)
LidarLocator * lidar_locator_
LocalizationLidar()
The constructor.
apollo::localization::msf::pyramid_map::PyramidMapConfig PyramidMapConfig
apollo::localization::msf::pyramid_map::PyramidMapNode PyramidMapNode
The class of LocalizationIntegParam
std::vector< double > pt_ys
std::vector< double > pt_xs
std::vector< unsigned char > intensities
std::vector< double > pt_zs
MapNodeData(const int w, const int h)