00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #ifndef _LIDAR_EGOMOTION_H_
00033 #define _LIDAR_EGOMOTION_H_
00034
00035 #include <iostream>
00036 #include <fstream>
00037
00038 #include <ros/ros.h>
00039
00040 #include <laser_geometry/laser_geometry.h>
00041
00042 #include <sensor_msgs/LaserScan.h>
00043 #include <sensor_msgs/PointCloud2.h>
00044
00045 #include <tf/transform_listener.h>
00046
00047 #include <pcl_ros/transforms.h>
00048 #include <pcl/ros/conversions.h>
00049 #include <pcl/point_cloud.h>
00050 #include <pcl/point_types.h>
00051
00052 #include <csm/csm_all.h>
00053 #include <csm/laser_data.h>
00054 #include "psm/polar_match.h"
00055 #include "mbicp/MbICP2.h"
00056
00057 #include <atlascar_base/AtlascarStatus.h>
00058 #include <atlascar_base/AtlascarVelocityStatus.h>
00059
00060 #include "motion_model.h"
00061 #include "plplot_graph.h"
00062 #include "types_declaration.h"
00063
00064 using namespace std;
00065
00066 void CleanZone(ray_definition*rays,double steering_angle);
00067 void SetDefaultConfiguration(void);
00068 void ConfigurePLICP(struct sm_params*params,LDP ref,LDP sens);
00069 pcl::PointCloud<pcl::PointXYZ> wrapper_Laserscan2PointCloud(const sensor_msgs::LaserScan& scan);
00070 void laser_2_Handler(const sensor_msgs::LaserScan& scan);
00071 void laser_3_Handler(const sensor_msgs::LaserScan& scan);
00072 void plcStatusHandler(const atlascar_base::AtlascarStatus& scan);
00073 void velocityStatusHandler(const atlascar_base::AtlascarVelocityStatus& scan);
00074
00075 void RaysToLDP(ray_definition*src,LDP dst,bool test_angle=0,double angle=M_PI/2.5);
00076 void RaysToLDP(ray_config_t*cfg,ray_measurment_t*src,LDP dst,bool test_angle=0,double angle=M_PI/2.5);
00077 void RaysToPMScan(ray_config_t*cfg,ray_measurment_t*src,PMScan*dst);
00078 void RaysToPMScan(ray_definition*src,PMScan*dst);
00079 int RaysToMbICP(ray_config_t*cfg,ray_measurment_t*src,Tpfp*dst,bool test_angle=0,double angle=M_PI/2.2);
00080 int RaysToMbICP(ray_definition*src,Tpfp*dst);
00081 void ConvertEstimatedToMeasurment(double vl,double dir,float*dx,float*dy,float*dtheta,double dt,double l,double bwa);
00082 void CreateMeasurementFromDisplacement(double dx,double dy,double dtheta,double z[2],double dt,double l,double bwa);
00083
00084
00085
00086
00087 #endif
00088