#include <math.h>
#include <time.h>
#include <stdio.h>
#include <stdlib.h>
#include <ros/ros.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
#include <opencv/cv.h>
#include <opencv2/highgui/highgui.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
Go to the source code of this file.
Functions | |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | coeffSel (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::KdTreeFLANN < pcl::PointXYZHSV >::Ptr | kdtreeCornerFromMap (new pcl::KdTreeFLANN< pcl::PointXYZHSV >()) |
pcl::KdTreeFLANN < pcl::PointXYZHSV >::Ptr | kdtreeSurfFromMap (new pcl::KdTreeFLANN< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudCorner (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudCorner2 (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudCornerFromMap (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudFromMap (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudLast (new pcl::PointCloud< pcl::PointXYZHSV >()) |
void | laserCloudLastHandler (const sensor_msgs::PointCloud2ConstPtr &laserCloudLast2) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudOri (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudSurf (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudSurf2 (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudSurfFromMap (new pcl::PointCloud< pcl::PointXYZHSV >()) |
pcl::PointCloud < pcl::PointXYZI >::Ptr | laserCloudSurround (new pcl::PointCloud< pcl::PointXYZI >()) |
void | laserOdometryHandler (const nav_msgs::Odometry::ConstPtr &laserOdometry) |
int | main (int argc, char **argv) |
void | pointAssociateToMap (pcl::PointXYZHSV *pi, pcl::PointXYZHSV *po) |
void | transformAssociateToMap () |
void | transformUpdate () |
Variables | |
const double | deg2rad = PI / 180 |
pcl::PointCloud < pcl::PointXYZHSV >::Ptr | laserCloudArray [laserCloudNum] |
const int | laserCloudCenDepth = 5 |
const int | laserCloudCenHeight = 5 |
const int | laserCloudCenWidth = 5 |
const int | laserCloudDepth = 11 |
const int | laserCloudHeight = 11 |
const int | laserCloudNum = laserCloudWidth * laserCloudHeight * laserCloudDepth |
int | laserCloudSurroundInd [27] |
int | laserCloudValidInd [27] |
const int | laserCloudWidth = 11 |
bool | newLaserCloudLast = false |
bool | newLaserOdometry = false |
const double | PI = 3.1415926 |
const double | rad2deg = 180 / PI |
double | timeLaserCloudLast |
double | timeLaserOdometry |
float | transformAftMapped [6] = {0} |
float | transformBefMapped [6] = {0} |
float | transformIncre [6] = {0} |
float | transformSum [6] = {0} |
float | transformTobeMapped [6] = {0} |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr coeffSel | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeCornerFromMap | ( | new pcl::KdTreeFLANN< pcl::PointXYZHSV > | () | ) |
pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeSurfFromMap | ( | new pcl::KdTreeFLANN< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCorner | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCorner2 | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCornerFromMap | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudFromMap | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudLast | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
void laserCloudLastHandler | ( | const sensor_msgs::PointCloud2ConstPtr & | laserCloudLast2 | ) |
Definition at line 192 of file laserMapping.cpp.
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudOri | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurf | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurf2 | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurfFromMap | ( | new pcl::PointCloud< pcl::PointXYZHSV > | () | ) |
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurround | ( | new pcl::PointCloud< pcl::PointXYZI > | () | ) |
void laserOdometryHandler | ( | const nav_msgs::Odometry::ConstPtr & | laserOdometry | ) |
Definition at line 202 of file laserMapping.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 221 of file laserMapping.cpp.
void pointAssociateToMap | ( | pcl::PointXYZHSV * | pi, |
pcl::PointXYZHSV * | po | ||
) |
Definition at line 170 of file laserMapping.cpp.
void transformAssociateToMap | ( | ) |
Definition at line 69 of file laserMapping.cpp.
void transformUpdate | ( | ) |
Definition at line 158 of file laserMapping.cpp.
Definition at line 25 of file laserMapping.cpp.
pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudArray[laserCloudNum] |
Definition at line 58 of file laserMapping.cpp.
const int laserCloudCenDepth = 5 |
Definition at line 35 of file laserMapping.cpp.
const int laserCloudCenHeight = 5 |
Definition at line 34 of file laserMapping.cpp.
const int laserCloudCenWidth = 5 |
Definition at line 33 of file laserMapping.cpp.
const int laserCloudDepth = 11 |
Definition at line 38 of file laserMapping.cpp.
const int laserCloudHeight = 11 |
Definition at line 37 of file laserMapping.cpp.
const int laserCloudNum = laserCloudWidth * laserCloudHeight * laserCloudDepth |
Definition at line 39 of file laserMapping.cpp.
int laserCloudSurroundInd[27] |
Definition at line 42 of file laserMapping.cpp.
int laserCloudValidInd[27] |
Definition at line 41 of file laserMapping.cpp.
const int laserCloudWidth = 11 |
Definition at line 36 of file laserMapping.cpp.
bool newLaserCloudLast = false |
Definition at line 30 of file laserMapping.cpp.
bool newLaserOdometry = false |
Definition at line 31 of file laserMapping.cpp.
const double PI = 3.1415926 |
Definition at line 23 of file laserMapping.cpp.
Definition at line 24 of file laserMapping.cpp.
double timeLaserCloudLast |
Definition at line 27 of file laserMapping.cpp.
double timeLaserOdometry |
Definition at line 28 of file laserMapping.cpp.
float transformAftMapped[6] = {0} |
Definition at line 67 of file laserMapping.cpp.
float transformBefMapped[6] = {0} |
Definition at line 66 of file laserMapping.cpp.
float transformIncre[6] = {0} |
Definition at line 64 of file laserMapping.cpp.
float transformSum[6] = {0} |
Definition at line 63 of file laserMapping.cpp.
float transformTobeMapped[6] = {0} |
Definition at line 65 of file laserMapping.cpp.