Functions | Variables
lidar_egomotion.cpp File Reference

Egomotion from lidar main source code. More...

#include "lidar_egomotion.h"
Include dependency graph for lidar_egomotion.cpp:

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)
 
int main (int argc, char **argv)
 
void RaysToLDP (ray_definition *src, LDP dst, bool test_angle, double angle)
 
void RaysToLDP (ray_config_t *cfg, ray_measurment_t *src, LDP dst, bool test_angle, double angle)
 
int RaysToMbICP (ray_definition *src, Tpfp *dst)
 
int RaysToMbICP (ray_config_t *cfg, ray_measurment_t *src, Tpfp *dst, bool test_angle, double angle)
 
void RaysToPMScan (ray_definition *src, PMScan *dst)
 
void RaysToPMScan (ray_config_t *cfg, ray_measurment_t *src, PMScan *dst)
 
void SetDefaultConfiguration (void)
 
pcl::PointCloud< pcl::PointXYZ > wrapper_Laserscan2PointCloud (const sensor_msgs::LaserScan &scan)
 

Variables

double bwa =3.40
 
ray_definition c_rays
 
t_flag flags
 
Tpfpfp1 =NULL
 
Tpfpfp2 =NULL
 
Tpfpfp3 =NULL
 
double gl =2.6
 
ray_history h_rays
 
ray_definitionl2_rays =NULL
 
ray_definitionl_rays =NULL
 
LDP ldp_1 =NULL
 
LDP ldp_2 =NULL
 
std::vector< pair< double,
double > > 
measurments
 
bool new_laser_2 =false
 
bool new_laser_3 =false
 
bool new_plc_status =false
 
bool new_velocity_status =false
 
std::vector< pair< double,
double > > 
odometry_readings
 
TSMparams params
 
struct sm_params params_sm
 
std::vector< t_posePtrpath_laser
 
std::vector< t_posePtrpath_odo
 
PMScan pm1
 
PMScan pm2
 
pcl::PointCloud< pcl::PointXYZ > point_cloud_2
 
pcl::PointCloud< pcl::PointXYZ > point_cloud_3
 
struct sm_result results_sm
 
std::vector< double > runtime_MbICP
 
std::vector< double > runtime_PlICP
 
std::vector< double > runtime_PSM
 
scan_matching_method scan_method = MBICP
 
Tsc sensorMotion
 
Tsc solution
 
Tsc solution2
 
int step =2
 
tf::TransformListener * transform_listener
 
double z [2]
 

Detailed Description

Egomotion from lidar main source code.

Definition in file lidar_egomotion.cpp.

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 760 of file lidar_egomotion.cpp.

void laser_3_Handler ( const sensor_msgs::LaserScan &  scan)

Definition at line 766 of file lidar_egomotion.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 784 of file lidar_egomotion.cpp.

void RaysToLDP ( ray_definition src,
LDP  dst,
bool  test_angle,
double  angle 
)

Definition at line 330 of file lidar_egomotion.cpp.

void RaysToLDP ( ray_config_t cfg,
ray_measurment_t src,
LDP  dst,
bool  test_angle,
double  angle 
)

Definition at line 353 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,
double  angle 
)

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.

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

Definition at line 722 of file lidar_egomotion.cpp.

Variable Documentation

double bwa =3.40

Definition at line 59 of file lidar_egomotion.cpp.

Definition at line 34 of file lidar_egomotion.cpp.

t_flag flags

Definition at line 64 of file lidar_egomotion.cpp.

Tpfp* fp1 =NULL

Definition at line 55 of file lidar_egomotion.cpp.

Tpfp* fp2 =NULL

Definition at line 56 of file lidar_egomotion.cpp.

Tpfp* fp3 =NULL

Definition at line 57 of file lidar_egomotion.cpp.

double gl =2.6

Definition at line 60 of file lidar_egomotion.cpp.

ray_history h_rays

Definition at line 35 of file lidar_egomotion.cpp.

ray_definition* l2_rays =NULL

Definition at line 37 of file lidar_egomotion.cpp.

ray_definition* l_rays =NULL

Definition at line 36 of file lidar_egomotion.cpp.

LDP ldp_1 =NULL

Definition at line 49 of file lidar_egomotion.cpp.

LDP ldp_2 =NULL

Definition at line 50 of file lidar_egomotion.cpp.

std::vector<pair<double,double> > measurments

Definition at line 74 of file lidar_egomotion.cpp.

bool new_laser_2 =false

Definition at line 79 of file lidar_egomotion.cpp.

bool new_laser_3 =false

Definition at line 80 of file lidar_egomotion.cpp.

bool new_plc_status =false

Definition at line 81 of file lidar_egomotion.cpp.

bool new_velocity_status =false

Definition at line 82 of file lidar_egomotion.cpp.

std::vector<pair<double,double> > odometry_readings

Definition at line 73 of file lidar_egomotion.cpp.

TSMparams params

Definition at line 103 of file MbICP.c.

struct sm_params params_sm

Definition at line 42 of file lidar_egomotion.cpp.

std::vector<t_posePtr> path_laser

Definition at line 67 of file lidar_egomotion.cpp.

std::vector<t_posePtr> path_odo

Definition at line 66 of file lidar_egomotion.cpp.

PMScan pm1

Definition at line 52 of file lidar_egomotion.cpp.

PMScan pm2

Definition at line 53 of file lidar_egomotion.cpp.

pcl::PointCloud<pcl::PointXYZ> point_cloud_2

Definition at line 77 of file lidar_egomotion.cpp.

pcl::PointCloud<pcl::PointXYZ> point_cloud_3

Definition at line 78 of file lidar_egomotion.cpp.

struct sm_result results_sm

Definition at line 43 of file lidar_egomotion.cpp.

std::vector<double> runtime_MbICP

Definition at line 70 of file lidar_egomotion.cpp.

std::vector<double> runtime_PlICP

Definition at line 69 of file lidar_egomotion.cpp.

std::vector<double> runtime_PSM

Definition at line 71 of file lidar_egomotion.cpp.

scan_matching_method scan_method = MBICP

Definition at line 39 of file lidar_egomotion.cpp.

Tsc sensorMotion

Definition at line 45 of file lidar_egomotion.cpp.

Tsc solution

Definition at line 45 of file lidar_egomotion.cpp.

Tsc solution2

Definition at line 45 of file lidar_egomotion.cpp.

int step =2

Definition at line 47 of file lidar_egomotion.cpp.

tf::TransformListener* transform_listener

Definition at line 76 of file lidar_egomotion.cpp.

double z[2]

Definition at line 62 of file lidar_egomotion.cpp.



lidar_egomotion
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:10