Functions |
void | laserCloudLastHandler (const sensor_msgs::PointCloud2ConstPtr &laserCloudLast2) |
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 |
pcl::PointCloud
< pcl::PointXYZHSV >::Ptr | coeffSel (new pcl::PointCloud< pcl::PointXYZHSV >()) |
const double | deg2rad = PI / 180 |
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 | laserCloudArray [laserCloudNum] |
const int | laserCloudCenDepth = 5 |
const int | laserCloudCenHeight = 5 |
const int | laserCloudCenWidth = 5 |
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 >()) |
const int | laserCloudDepth = 11 |
pcl::PointCloud
< pcl::PointXYZHSV >::Ptr | laserCloudFromMap (new pcl::PointCloud< pcl::PointXYZHSV >()) |
const int | laserCloudHeight = 11 |
pcl::PointCloud
< pcl::PointXYZHSV >::Ptr | laserCloudLast (new pcl::PointCloud< pcl::PointXYZHSV >()) |
const int | laserCloudNum = laserCloudWidth * laserCloudHeight * laserCloudDepth |
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 >()) |
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} |