23#include "Eigen/Geometry"
24#include "pcl/point_cloud.h"
25#include "pcl/point_types.h"
34#define USE_PRELOAD_MAP_NODE
37#define VIS_USE_OPENCV_ON
39#ifdef VIS_USE_OPENCV_ON
40#include <opencv2/opencv.hpp>
41void color_mapping(
float value,
float midvalue,
unsigned char* r,
42 unsigned char* g,
unsigned char* b) {
45 }
else if (value < 0.f) {
48 if (value > midvalue) {
49 value = (value - midvalue) / (1.f - midvalue);
51 *g = (1.0 - value) * 255.0;
57 *b = (1 - value) * 255.0;
63namespace localization {
91 void LoadMap(
const Eigen::Affine3d& init_location,
unsigned int resolution_id,
94 void Init(
const Eigen::Affine3d& init_location,
unsigned int resolution_id,
104 void ComposeMapCells(
const Eigen::Vector2d& left_top_coord2d,
int zone_id,
105 unsigned int resolution_id,
float map_pixel_resolution,
106 const Eigen::Affine3d& inverse_transform);
114 int Update(
unsigned int frame_idx,
const Eigen::Affine3d& pose,
117 Eigen::Affine3d
GetPose()
const;
133 bool is_initialized_ =
false;
135 bool is_map_loaded_ =
false;
138 Eigen::Affine3d location_;
140 Eigen::Matrix3d location_covariance_;
142 Eigen::Affine3d predict_location_;
144 Eigen::Affine3d pre_input_location_;
146 Eigen::Affine3d pre_estimate_location_;
149 unsigned int resolution_id_ = 0;
154 double lidar_height_ = 1.7;
156 double pre_imu_height_ = 0;
158 Eigen::Affine3d velodyne_extrinsic_;
164 float proj_reslution_ = 1.0;
173 std::vector<Leaf> cell_map_;
175 Eigen::Vector3d map_left_top_corner_;
180 double fitness_score_ = 0.0;
183 int ndt_max_iterations_ = 10;
184 double ndt_target_resolution_ = 1.0;
185 double ndt_line_search_step_size_ = 0.1;
186 double ndt_transformation_epsilon_ = 0.01;
189 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
The data structure of ndt Map cell.
The options of the reflectance map.
The data structure of ndt Map matrix.
The memory pool for the data structure of BaseMapNode.
void SetVelodyneExtrinsic(const Eigen::Affine3d &extrinsic)
Set the extrinsic calibration.
bool IsInitialized() const
Is the locator initialized.
void SetMapFolderPath(const std::string folder_path)
Set the map folder.
int Update(unsigned int frame_idx, const Eigen::Affine3d &pose, const LidarFrame &lidar_frame)
Update the histogram filter.
~LidarLocatorNdt()
The destructor.
const NdtMap & GetMap() const
Get the locator map.
void Init(const Eigen::Affine3d &init_location, unsigned int resolution_id, int zone_id)
Initialize the locator.
LidarLocatorNdt()
The constructor.
void SetOnlineCloudResolution(const float &online_resolution)
Set online cloud resolution.
Eigen::Matrix3d GetLocationCovariance() const
Get the covariance of estimated location.
Eigen::Affine3d GetPose() const
Get the current optimal pose result.
void SetLidarHeight(double height)
Set the lidar height.
void ComposeMapCells(const Eigen::Vector2d &left_top_coord2d, int zone_id, unsigned int resolution_id, float map_pixel_resolution, const Eigen::Affine3d &inverse_transform)
Compose candidate map area.
bool IsMaploaded() const
Is the map data loaded.
Eigen::Vector3d GetPredictLocation() const
void LoadMap(const Eigen::Affine3d &init_location, unsigned int resolution_id, int zone_id)
Load map data.
double GetFitnessScore() const
Get ndt matching score
apollo::localization::msf::pyramid_map::NdtMapConfig NdtMapConfig
apollo::localization::msf::pyramid_map::NdtMapCells NdtMapCells
apollo::localization::msf::pyramid_map::NdtMap NdtMap
apollo::localization::msf::pyramid_map::MapNodeIndex MapNodeIndex
apollo::localization::msf::pyramid_map::NdtMapMatrix NdtMapMatrix
apollo::localization::msf::pyramid_map::NdtMapNode NdtMapNode
apollo::localization::msf::pyramid_map::NdtMapNodePool NdtMapNodePool
std::vector< float > pt_ys
std::vector< float > pt_zs
std::vector< unsigned char > intensities
std::vector< float > pt_xs