/home/laradmin/lar/perception/lidar_egomotion/src/lidar_egomotion.h File Reference

Egomotion from lidar main header. More...

#include <iostream>
#include <fstream>
#include <ros/ros.h>
#include <laser_geometry/laser_geometry.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_listener.h>
#include <pcl_ros/transforms.h>
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <csm/csm_all.h>
#include <csm/laser_data.h>
#include "psm/polar_match.h"
#include "mbicp/MbICP2.h"
#include <atlascar_base/AtlascarStatus.h>
#include <atlascar_base/AtlascarVelocityStatus.h>
#include "motion_model.h"
#include "plplot_graph.h"
#include <plplot.h>
#include <string>
#include <stdlib.h>
#include <math.h>
#include <iomanip>
#include <boost/shared_ptr.hpp>
#include <boost/bind.hpp>
#include <vector>
#include <assert.h>
#include <string.h>
#include <float.h>
#include <stdint.h>
#include "opencv2/core/types_c.h"
#include <limits.h>
#include "opencv2/core/core_c.h"
#include "opencv2/imgproc/types_c.h"
#include "opencv2/core/core.hpp"
#include "opencv2/imgproc/imgproc_c.h"
#include "opencv2/features2d/features2d.hpp"
#include <cxcore.h>
#include "types_declaration.h"
Include dependency graph for lidar_egomotion.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

void CleanZone (ray_definition *rays, double steering_angle)
void ConfigurePLICP (struct sm_params *params, LDP ref, LDP sens)
void ConvertEstimatedToMeasurment (double vl, double dir, float *dx, float *dy, float *dtheta, double dt, double l, double bwa)
void CreateMeasurementFromDisplacement (double dx, double dy, double dtheta, double z[2], double dt, double l, double bwa)
void laser_2_Handler (const sensor_msgs::LaserScan &scan)
void laser_3_Handler (const sensor_msgs::LaserScan &scan)
void plcStatusHandler (const atlascar_base::AtlascarStatus &scan)
void RaysToLDP (ray_config_t *cfg, ray_measurment_t *src, LDP dst, bool test_angle=0, double angle=M_PI/2.5)
void RaysToLDP (ray_definition *src, LDP dst, bool test_angle=0, double angle=M_PI/2.5)
int RaysToMbICP (ray_definition *src, Tpfp *dst)
int RaysToMbICP (ray_config_t *cfg, ray_measurment_t *src, Tpfp *dst, bool test_angle=0, double angle=M_PI/2.2)
void RaysToPMScan (ray_definition *src, PMScan *dst)
void RaysToPMScan (ray_config_t *cfg, ray_measurment_t *src, PMScan *dst)
void SetDefaultConfiguration (void)
void velocityStatusHandler (const atlascar_base::AtlascarVelocityStatus &scan)
pcl::PointCloud< pcl::PointXYZ > wrapper_Laserscan2PointCloud (const sensor_msgs::LaserScan &scan)

Detailed Description

Egomotion from lidar main header.

Definition in file lidar_egomotion.h.


Function Documentation

void CleanZone ( ray_definition rays,
double  steering_angle 
)

Definition at line 84 of file lidar_egomotion.cpp.

void ConfigurePLICP ( struct sm_params *  params,
LDP  ref,
LDP  sens 
)

A threshold for stopping.

A threshold for stopping.

Maximum angular displacement between scans (deg)

Maximum translation between scans (m)

Noise in the scan

Percentage of correspondences to consider: if 0.9, always discard the top 10% of correspondences with more error

Definition at line 667 of file lidar_egomotion.cpp.

void ConvertEstimatedToMeasurment ( double  vl,
double  dir,
float *  dx,
float *  dy,
float *  dtheta,
double  dt,
double  l,
double  bwa 
)

Definition at line 243 of file lidar_egomotion.cpp.

void CreateMeasurementFromDisplacement ( double  dx,
double  dy,
double  dtheta,
double  z[2],
double  dt,
double  l,
double  bwa 
)

Definition at line 535 of file lidar_egomotion.cpp.

void laser_2_Handler ( const sensor_msgs::LaserScan &  scan  ) 

Definition at line 757 of file lidar_egomotion.cpp.

void laser_3_Handler ( const sensor_msgs::LaserScan &  scan  ) 

Definition at line 763 of file lidar_egomotion.cpp.

void plcStatusHandler ( const atlascar_base::AtlascarStatus &  scan  ) 

Definition at line 769 of file lidar_egomotion.cpp.

void RaysToLDP ( ray_config_t cfg,
ray_measurment_t src,
LDP  dst,
bool  test_angle = 0,
double  angle = M_PI/2.5 
)

Definition at line 353 of file lidar_egomotion.cpp.

void RaysToLDP ( ray_definition src,
LDP  dst,
bool  test_angle = 0,
double  angle = M_PI/2.5 
)

Definition at line 330 of file lidar_egomotion.cpp.

int RaysToMbICP ( ray_definition src,
Tpfp dst 
)

Definition at line 426 of file lidar_egomotion.cpp.

int RaysToMbICP ( ray_config_t cfg,
ray_measurment_t src,
Tpfp dst,
bool  test_angle = 0,
double  angle = M_PI/2.2 
)

Definition at line 442 of file lidar_egomotion.cpp.

void RaysToPMScan ( ray_definition src,
PMScan dst 
)

Definition at line 225 of file lidar_egomotion.cpp.

void RaysToPMScan ( ray_config_t cfg,
ray_measurment_t src,
PMScan dst 
)

Definition at line 295 of file lidar_egomotion.cpp.

void SetDefaultConfiguration ( void   ) 

Definition at line 611 of file lidar_egomotion.cpp.

void velocityStatusHandler ( const atlascar_base::AtlascarVelocityStatus &  scan  ) 

Definition at line 775 of file lidar_egomotion.cpp.

pcl::PointCloud<pcl::PointXYZ> wrapper_Laserscan2PointCloud ( const sensor_msgs::LaserScan &  scan  ) 

Definition at line 722 of file lidar_egomotion.cpp.

 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


lidar_egomotion
Author(s): Jorge Almeida
autogenerated on Wed Jul 23 04:34:38 2014