Functions | Variables
laserMapping.cpp File Reference
#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>
Include dependency graph for laserMapping.cpp:

Go to the source code of this file.

Functions

pcl::PointCloud
< pcl::PointXYZI >::Ptr 
coeffSel (new pcl::PointCloud< pcl::PointXYZI >())
void imuHandler (const sensor_msgs::Imu::ConstPtr &imuIn)
pcl::KdTreeFLANN
< pcl::PointXYZI >::Ptr 
kdtreeCornerFromMap (new pcl::KdTreeFLANN< pcl::PointXYZI >())
pcl::KdTreeFLANN
< pcl::PointXYZI >::Ptr 
kdtreeSurfFromMap (new pcl::KdTreeFLANN< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudCornerFromMap (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudCornerLast (new pcl::PointCloud< pcl::PointXYZI >())
void laserCloudCornerLastHandler (const sensor_msgs::PointCloud2ConstPtr &laserCloudCornerLast2)
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudCornerStack (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudCornerStack2 (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudFullRes (new pcl::PointCloud< pcl::PointXYZI >())
void laserCloudFullResHandler (const sensor_msgs::PointCloud2ConstPtr &laserCloudFullRes2)
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudOri (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurfFromMap (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurfLast (new pcl::PointCloud< pcl::PointXYZI >())
void laserCloudSurfLastHandler (const sensor_msgs::PointCloud2ConstPtr &laserCloudSurfLast2)
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurfStack (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurfStack2 (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurround (new pcl::PointCloud< pcl::PointXYZI >())
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurround2 (new pcl::PointCloud< pcl::PointXYZI >())
void laserOdometryHandler (const nav_msgs::Odometry::ConstPtr &laserOdometry)
int main (int argc, char **argv)
void pointAssociateTobeMapped (pcl::PointXYZI *pi, pcl::PointXYZI *po)
void pointAssociateToMap (pcl::PointXYZI *pi, pcl::PointXYZI *po)
void transformAssociateToMap ()
void transformUpdate ()

Variables

float imuPitch [imuQueLength] = {0}
int imuPointerFront = 0
int imuPointerLast = -1
const int imuQueLength = 200
float imuRoll [imuQueLength] = {0}
double imuTime [imuQueLength] = {0}
int laserCloudCenDepth = 10
int laserCloudCenHeight = 5
int laserCloudCenWidth = 10
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudCornerArray [laserCloudNum]
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudCornerArray2 [laserCloudNum]
const int laserCloudDepth = 21
const int laserCloudHeight = 11
const int laserCloudNum = laserCloudWidth * laserCloudHeight * laserCloudDepth
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurfArray [laserCloudNum]
pcl::PointCloud
< pcl::PointXYZI >::Ptr 
laserCloudSurfArray2 [laserCloudNum]
int laserCloudSurroundInd [125]
int laserCloudValidInd [125]
const int laserCloudWidth = 21
const int mapFrameNum = 5
bool newLaserCloudCornerLast = false
bool newLaserCloudFullRes = false
bool newLaserCloudSurfLast = false
bool newLaserOdometry = false
const double PI = 3.1415926
const float scanPeriod = 0.1
const int stackFrameNum = 1
double timeLaserCloudCornerLast = 0
double timeLaserCloudFullRes = 0
double timeLaserCloudSurfLast = 0
double timeLaserOdometry = 0
float transformAftMapped [6] = {0}
float transformBefMapped [6] = {0}
float transformIncre [6] = {0}
float transformSum [6] = {0}
float transformTobeMapped [6] = {0}

Function Documentation

pcl::PointCloud<pcl::PointXYZI>::Ptr coeffSel ( new pcl::PointCloud< pcl::PointXYZI >  ())
void imuHandler ( const sensor_msgs::Imu::ConstPtr &  imuIn)

Definition at line 305 of file laserMapping.cpp.

pcl::KdTreeFLANN<pcl::PointXYZI>::Ptr kdtreeCornerFromMap ( new pcl::KdTreeFLANN< pcl::PointXYZI >  ())
pcl::KdTreeFLANN<pcl::PointXYZI>::Ptr kdtreeSurfFromMap ( new pcl::KdTreeFLANN< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudCornerFromMap ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudCornerLast ( new pcl::PointCloud< pcl::PointXYZI >  ())
void laserCloudCornerLastHandler ( const sensor_msgs::PointCloud2ConstPtr &  laserCloudCornerLast2)

Definition at line 256 of file laserMapping.cpp.

pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudCornerStack ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudCornerStack2 ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudFullRes ( new pcl::PointCloud< pcl::PointXYZI >  ())
void laserCloudFullResHandler ( const sensor_msgs::PointCloud2ConstPtr &  laserCloudFullRes2)

Definition at line 276 of file laserMapping.cpp.

pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudOri ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurfFromMap ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurfLast ( new pcl::PointCloud< pcl::PointXYZI >  ())
void laserCloudSurfLastHandler ( const sensor_msgs::PointCloud2ConstPtr &  laserCloudSurfLast2)

Definition at line 266 of file laserMapping.cpp.

pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurfStack ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurfStack2 ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurround ( new pcl::PointCloud< pcl::PointXYZI >  ())
pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurround2 ( new pcl::PointCloud< pcl::PointXYZI >  ())
void laserOdometryHandler ( const nav_msgs::Odometry::ConstPtr &  laserOdometry)

Definition at line 286 of file laserMapping.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 319 of file laserMapping.cpp.

void pointAssociateTobeMapped ( pcl::PointXYZI *  pi,
pcl::PointXYZI *  po 
)

Definition at line 236 of file laserMapping.cpp.

void pointAssociateToMap ( pcl::PointXYZI *  pi,
pcl::PointXYZI *  po 
)

Definition at line 216 of file laserMapping.cpp.

Definition at line 89 of file laserMapping.cpp.

void transformUpdate ( )

Definition at line 178 of file laserMapping.cpp.


Variable Documentation

float imuPitch[imuQueLength] = {0}

Definition at line 87 of file laserMapping.cpp.

int imuPointerFront = 0

Definition at line 81 of file laserMapping.cpp.

int imuPointerLast = -1

Definition at line 82 of file laserMapping.cpp.

const int imuQueLength = 200

Definition at line 83 of file laserMapping.cpp.

float imuRoll[imuQueLength] = {0}

Definition at line 86 of file laserMapping.cpp.

double imuTime[imuQueLength] = {0}

Definition at line 85 of file laserMapping.cpp.

Definition at line 42 of file laserMapping.cpp.

Definition at line 41 of file laserMapping.cpp.

Definition at line 40 of file laserMapping.cpp.

Definition at line 67 of file laserMapping.cpp.

Definition at line 69 of file laserMapping.cpp.

const int laserCloudDepth = 21

Definition at line 45 of file laserMapping.cpp.

const int laserCloudHeight = 11

Definition at line 44 of file laserMapping.cpp.

Definition at line 46 of file laserMapping.cpp.

Definition at line 68 of file laserMapping.cpp.

Definition at line 70 of file laserMapping.cpp.

Definition at line 49 of file laserMapping.cpp.

Definition at line 48 of file laserMapping.cpp.

const int laserCloudWidth = 21

Definition at line 43 of file laserMapping.cpp.

const int mapFrameNum = 5

Definition at line 28 of file laserMapping.cpp.

Definition at line 35 of file laserMapping.cpp.

bool newLaserCloudFullRes = false

Definition at line 37 of file laserMapping.cpp.

bool newLaserCloudSurfLast = false

Definition at line 36 of file laserMapping.cpp.

bool newLaserOdometry = false

Definition at line 38 of file laserMapping.cpp.

const double PI = 3.1415926

Definition at line 23 of file laserMapping.cpp.

const float scanPeriod = 0.1

Definition at line 25 of file laserMapping.cpp.

const int stackFrameNum = 1

Definition at line 27 of file laserMapping.cpp.

Definition at line 30 of file laserMapping.cpp.

Definition at line 32 of file laserMapping.cpp.

Definition at line 31 of file laserMapping.cpp.

double timeLaserOdometry = 0

Definition at line 33 of file laserMapping.cpp.

float transformAftMapped[6] = {0}

Definition at line 79 of file laserMapping.cpp.

float transformBefMapped[6] = {0}

Definition at line 78 of file laserMapping.cpp.

float transformIncre[6] = {0}

Definition at line 76 of file laserMapping.cpp.

float transformSum[6] = {0}

Definition at line 75 of file laserMapping.cpp.

float transformTobeMapped[6] = {0}

Definition at line 77 of file laserMapping.cpp.



loam_velodyne
Author(s): Ji Zhang
autogenerated on Mon Nov 10 2014 13:32:12