lidar_mapping.hpp
Go to the documentation of this file.
1 
3 
4 // Original Author of FLOAM: Wang Han
5 // Email wh200720041@gmail.com
6 // Homepage https://wanghan.pro
7 #ifndef FLOAM__LIDAR_MAPPING_HPP_
8 #define FLOAM__LIDAR_MAPPING_HPP_
9 
10 //PCL lib
11 #include <pcl/point_cloud.h>
12 #include <pcl/point_types.h>
13 #include <pcl/filters/filter.h>
14 #include <pcl/filters/voxel_grid.h>
15 #include <pcl/filters/passthrough.h>
17 
18 //eigen lib
19 #include <Eigen/Dense>
20 #include <Eigen/Geometry>
21 
22 //c++ lib
23 #include <string>
24 #include <math.h>
25 #include <vector>
26 
27 
28 #define CELL_WIDTH 50.0 // m
29 #define CELL_HEIGHT 50.0 // m
30 #define CELL_DEPTH 50.0 // m
31 
32 #define CELL_RANGE_HORIZONTAL 4
33 #define CELL_RANGE_VERTICAL 4
34 #define HALF_CELL_RANGE_HORIZONTAL CELL_RANGE_HORIZONTAL / 2
35 #define HALF_CELL_RANGE_VERTICAL CELL_RANGE_VERTICAL / 2
36 
37 
38 namespace floam
39 {
40 namespace lidar
41 {
42 
44 {
45 public:
46  LidarMapping();
47  void init(const double & map_resolution);
49  const pcl::PointCloud<pcl::PointXYZL>::Ptr & pc_in,
50  const Eigen::Isometry3d & pose_current);
51  pcl::PointCloud<pcl::PointXYZL>::Ptr getMap(void);
52 
53 private:
56  std::vector<std::vector<std::vector<pcl::PointCloud<pcl::PointXYZL>::Ptr>>> m_map;
57  pcl::VoxelGrid<pcl::PointXYZL> m_downSizeFilter;
58 
59  void addWidthCellNegative(void);
60  void addWidthCellPositive(void);
61  void addHeightCellNegative(void);
62  void addHeightCellPositive(void);
63  void addDepthCellNegative(void);
64  void addDepthCellPositive(void);
65  void checkPoints(int & x, int & y, int & z);
66 };
67 
68 } // namespace lidar
69 } // namespace floam
70 
71 #endif // FLOAM__LIDAR_MAPPING_HPP_
72 
floam::lidar::LidarMapping::getMap
pcl::PointCloud< pcl::PointXYZL >::Ptr getMap(void)
Definition: lidar_mapping.cpp:208
floam::lidar::LidarMapping::addHeightCellNegative
void addHeightCellNegative(void)
Definition: lidar_mapping.cpp:82
floam::lidar::LidarMapping::addDepthCellPositive
void addDepthCellPositive(void)
Definition: lidar_mapping.cpp:120
floam::lidar::LidarMapping::m_downSizeFilter
pcl::VoxelGrid< pcl::PointXYZL > m_downSizeFilter
Definition: lidar_mapping.hpp:57
transforms.hpp
floam::lidar::LidarMapping::m_map
std::vector< std::vector< std::vector< pcl::PointCloud< pcl::PointXYZL >::Ptr > > > m_map
Definition: lidar_mapping.hpp:56
floam::lidar::LidarMapping
Definition: lidar_mapping.hpp:43
floam::lidar::LidarMapping::m_originInMapY
int m_originInMapY
Definition: lidar_mapping.hpp:54
floam::lidar::LidarMapping::LidarMapping
LidarMapping()
Definition: lidar_mapping.cpp:16
floam::lidar::LidarMapping::addWidthCellNegative
void addWidthCellNegative(void)
Definition: lidar_mapping.cpp:49
floam::lidar::LidarMapping::m_originInMapZ
int m_originInMapZ
Definition: lidar_mapping.hpp:54
floam::lidar::LidarMapping::m_originInMapX
int m_originInMapX
Definition: lidar_mapping.hpp:54
floam::lidar::LidarMapping::checkPoints
void checkPoints(int &x, int &y, int &z)
Definition: lidar_mapping.cpp:132
floam::lidar::LidarMapping::m_mapWidth
int m_mapWidth
Definition: lidar_mapping.hpp:55
floam::lidar::LidarMapping::addDepthCellNegative
void addDepthCellNegative(void)
Definition: lidar_mapping.cpp:109
floam::lidar::LidarMapping::m_mapDepth
int m_mapDepth
Definition: lidar_mapping.hpp:55
floam::lidar::LidarMapping::init
void init(const double &map_resolution)
Definition: lidar_mapping.cpp:21
floam::lidar::LidarMapping::addWidthCellPositive
void addWidthCellPositive(void)
Definition: lidar_mapping.cpp:66
floam::lidar::LidarMapping::addHeightCellPositive
void addHeightCellPositive(void)
Definition: lidar_mapping.cpp:96
floam::lidar::LidarMapping::updateCurrentPointsToMap
void updateCurrentPointsToMap(const pcl::PointCloud< pcl::PointXYZL >::Ptr &pc_in, const Eigen::Isometry3d &pose_current)
Definition: lidar_mapping.cpp:171
floam
Major rewrite Author: Evan Flynn.
Definition: lidar.hpp:15
floam::lidar::LidarMapping::m_mapHeight
int m_mapHeight
Definition: lidar_mapping.hpp:55


floam
Author(s): Han Wang
autogenerated on Wed Mar 2 2022 00:23:09