|
| 1 | +#ifndef _UTILITY_LIDAR_ODOMETRY_H_ |
| 2 | +#define _UTILITY_LIDAR_ODOMETRY_H_ |
| 3 | + |
| 4 | + |
| 5 | +#include <ros/ros.h> |
| 6 | + |
| 7 | +#include <sensor_msgs/Imu.h> |
| 8 | +#include <sensor_msgs/PointCloud2.h> |
| 9 | +#include <nav_msgs/Odometry.h> |
| 10 | + |
| 11 | +#include "cloud_msgs/cloud_info.h" |
| 12 | + |
| 13 | +#include <opencv/cv.h> |
| 14 | + |
| 15 | +#include <pcl/point_cloud.h> |
| 16 | +#include <pcl/point_types.h> |
| 17 | +#include <pcl_ros/point_cloud.h> |
| 18 | +#include <pcl_conversions/pcl_conversions.h> |
| 19 | +#include <pcl/range_image/range_image.h> |
| 20 | +#include <pcl/filters/filter.h> |
| 21 | +#include <pcl/filters/voxel_grid.h> |
| 22 | +#include <pcl/kdtree/kdtree_flann.h> |
| 23 | +#include <pcl/common/common.h> |
| 24 | +#include <pcl/registration/icp.h> |
| 25 | + |
| 26 | +#include <tf/transform_broadcaster.h> |
| 27 | +#include <tf/transform_datatypes.h> |
| 28 | + |
| 29 | +#include <vector> |
| 30 | +#include <cmath> |
| 31 | +#include <algorithm> |
| 32 | +#include <queue> |
| 33 | +#include <deque> |
| 34 | +#include <iostream> |
| 35 | +#include <fstream> |
| 36 | +#include <ctime> |
| 37 | +#include <cfloat> |
| 38 | +#include <iterator> |
| 39 | +#include <sstream> |
| 40 | +#include <string> |
| 41 | +#include <limits> |
| 42 | +#include <iomanip> |
| 43 | +#include <array> |
| 44 | +#include <thread> |
| 45 | +#include <mutex> |
| 46 | + |
| 47 | +#define PI 3.14159265 |
| 48 | + |
| 49 | +using namespace std; |
| 50 | + |
| 51 | +typedef pcl::PointXYZI PointType; |
| 52 | + |
| 53 | +extern const string pointCloudTopic = "/velodyne_points"; |
| 54 | +extern const string imuTopic = "/imu/data"; |
| 55 | + |
| 56 | +// Save pcd |
| 57 | +extern const string fileDirectory = "/tmp/"; |
| 58 | + |
| 59 | +// VLP-16 |
| 60 | +extern const int N_SCAN = 16; |
| 61 | +extern const int Horizon_SCAN = 1800; |
| 62 | +extern const float ang_res_x = 0.2; |
| 63 | +extern const float ang_res_y = 2.0; |
| 64 | +extern const float ang_bottom = 15.0+0.1; |
| 65 | +extern const int groundScanInd = 7; |
| 66 | + |
| 67 | +// HDL-32E |
| 68 | +// extern const int N_SCAN = 32; |
| 69 | +// extern const int Horizon_SCAN = 1800; |
| 70 | +// extern const float ang_res_x = 360.0/float(Horizon_SCAN); |
| 71 | +// extern const float ang_res_y = 41.33/float(N_SCAN-1); |
| 72 | +// extern const float ang_bottom = 30.67; |
| 73 | +// extern const int groundScanInd = 20; |
| 74 | + |
| 75 | +// Ouster users may need to uncomment line 159 in imageProjection.cpp |
| 76 | +// Usage of Ouster imu data is not fully supported yet, please just publish point cloud data |
| 77 | +// Ouster OS1-16 |
| 78 | +// extern const int N_SCAN = 16; |
| 79 | +// extern const int Horizon_SCAN = 1024; |
| 80 | +// extern const float ang_res_x = 360.0/float(Horizon_SCAN); |
| 81 | +// extern const float ang_res_y = 33.2/float(N_SCAN-1); |
| 82 | +// extern const float ang_bottom = 16.6+0.1; |
| 83 | +// extern const int groundScanInd = 7; |
| 84 | + |
| 85 | +// Ouster OS1-64 |
| 86 | +// extern const int N_SCAN = 64; |
| 87 | +// extern const int Horizon_SCAN = 1024; |
| 88 | +// extern const float ang_res_x = 360.0/float(Horizon_SCAN); |
| 89 | +// extern const float ang_res_y = 33.2/float(N_SCAN-1); |
| 90 | +// extern const float ang_bottom = 16.6+0.1; |
| 91 | +// extern const int groundScanInd = 15; |
| 92 | + |
| 93 | +extern const bool loopClosureEnableFlag = false; |
| 94 | +extern const double mappingProcessInterval = 0.3; |
| 95 | + |
| 96 | +extern const float scanPeriod = 0.1; |
| 97 | +extern const int systemDelay = 0; |
| 98 | +extern const int imuQueLength = 200; |
| 99 | + |
| 100 | +extern const float sensorMountAngle = 0.0; |
| 101 | +extern const float segmentTheta = 60.0/180.0*M_PI; // decrese this value may improve accuracy |
| 102 | +extern const int segmentValidPointNum = 5; |
| 103 | +extern const int segmentValidLineNum = 3; |
| 104 | +extern const float segmentAlphaX = ang_res_x / 180.0 * M_PI; |
| 105 | +extern const float segmentAlphaY = ang_res_y / 180.0 * M_PI; |
| 106 | + |
| 107 | + |
| 108 | +extern const int edgeFeatureNum = 2; |
| 109 | +extern const int surfFeatureNum = 4; |
| 110 | +extern const int sectionsTotal = 6; |
| 111 | +extern const float edgeThreshold = 0.1; |
| 112 | +extern const float surfThreshold = 0.1; |
| 113 | +extern const float nearestFeatureSearchSqDist = 25; |
| 114 | + |
| 115 | + |
| 116 | +// Mapping Params |
| 117 | +extern const float surroundingKeyframeSearchRadius = 50.0; // key frame that is within n meters from current pose will be considerd for scan-to-map optimization (when loop closure disabled) |
| 118 | +extern const int surroundingKeyframeSearchNum = 50; // submap size (when loop closure enabled) |
| 119 | +// history key frames (history submap for loop closure) |
| 120 | +extern const float historyKeyframeSearchRadius = 7.0; // key frame that is within n meters from current pose will be considerd for loop closure |
| 121 | +extern const int historyKeyframeSearchNum = 25; // 2n+1 number of hostory key frames will be fused into a submap for loop closure |
| 122 | +extern const float historyKeyframeFitnessScore = 0.3; // the smaller the better alignment |
| 123 | + |
| 124 | +extern const float globalMapVisualizationSearchRadius = 500.0; // key frames with in n meters will be visualized |
| 125 | + |
| 126 | + |
| 127 | +struct smoothness_t{ |
| 128 | + float value; |
| 129 | + size_t ind; |
| 130 | +}; |
| 131 | + |
| 132 | +struct by_value{ |
| 133 | + bool operator()(smoothness_t const &left, smoothness_t const &right) { |
| 134 | + return left.value < right.value; |
| 135 | + } |
| 136 | +}; |
| 137 | + |
| 138 | +/* |
| 139 | + * A point cloud type that has 6D pose info ([x,y,z,roll,pitch,yaw] intensity is time stamp) |
| 140 | + */ |
| 141 | +struct PointXYZIRPYT |
| 142 | +{ |
| 143 | + PCL_ADD_POINT4D |
| 144 | + PCL_ADD_INTENSITY; |
| 145 | + float roll; |
| 146 | + float pitch; |
| 147 | + float yaw; |
| 148 | + double time; |
| 149 | + EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
| 150 | +} EIGEN_ALIGN16; |
| 151 | + |
| 152 | +POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIRPYT, |
| 153 | + (float, x, x) (float, y, y) |
| 154 | + (float, z, z) (float, intensity, intensity) |
| 155 | + (float, roll, roll) (float, pitch, pitch) (float, yaw, yaw) |
| 156 | + (double, time, time) |
| 157 | +) |
| 158 | + |
| 159 | +typedef PointXYZIRPYT PointTypePose; |
| 160 | + |
| 161 | +#endif |
0 commit comments