lidar_egomotion.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #ifndef _LIDAR_EGOMOTION_H_
33 #define _LIDAR_EGOMOTION_H_
34 
35 #include <iostream>
36 #include <fstream>
37 
38 #include <ros/ros.h>
39 
40 #include <laser_geometry/laser_geometry.h>
41 
42 #include <sensor_msgs/LaserScan.h>
43 #include <sensor_msgs/PointCloud2.h>
44 
45 #include <tf/transform_listener.h>
46 
47 #include <pcl_ros/transforms.h>
48 #include <pcl/conversions.h>
49 #include <pcl/point_cloud.h>
50 #include <pcl/point_types.h>
51 #include <pcl_conversions/pcl_conversions.h>
52 
53 #include <csm/csm_all.h>//needed for the PLICP algorithm, external
54 #include <csm/laser_data.h>//needed for the PLICP algorithm, external
55 #include "psm/polar_match.h"//neeeded for the psm algorithm, internal
56 #include "mbicp/MbICP2.h"//neeeded for the psm algorithm, internal
57 
58 // #include <atlascar_base/AtlascarStatus.h>
59 // #include <atlascar_base/AtlascarVelocityStatus.h>
60 
61 #include "motion_model.h"
62 #include "plplot_graph.h"
63 #include "types_declaration.h"
64 
65 using namespace std;
66 
67 void CleanZone(ray_definition*rays,double steering_angle);
68 void SetDefaultConfiguration(void);
69 void ConfigurePLICP(struct sm_params*params,LDP ref,LDP sens);
70 pcl::PointCloud<pcl::PointXYZ> wrapper_Laserscan2PointCloud(const sensor_msgs::LaserScan& scan);
71 void laser_2_Handler(const sensor_msgs::LaserScan& scan);
72 void laser_3_Handler(const sensor_msgs::LaserScan& scan);
73 // void plcStatusHandler(const atlascar_base::AtlascarStatus& scan);
74 // void velocityStatusHandler(const atlascar_base::AtlascarVelocityStatus& scan);
75 
76 void RaysToLDP(ray_definition*src,LDP dst,bool test_angle=0,double angle=M_PI/2.5);
77 void RaysToLDP(ray_config_t*cfg,ray_measurment_t*src,LDP dst,bool test_angle=0,double angle=M_PI/2.5);
79 void RaysToPMScan(ray_definition*src,PMScan*dst);
80 int RaysToMbICP(ray_config_t*cfg,ray_measurment_t*src,Tpfp*dst,bool test_angle=0,double angle=M_PI/2.2);
81 int RaysToMbICP(ray_definition*src,Tpfp*dst);
82 void ConvertEstimatedToMeasurment(double vl,double dir,float*dx,float*dy,float*dtheta,double dt,double l,double bwa);
83 void CreateMeasurementFromDisplacement(double dx,double dy,double dtheta,double z[2],double dt,double l,double bwa);
84 
85 // extern "C" {
86 // extern LDP ld_alloc_new(int nrays);
87 // }
88 #endif
89 
double z[2]
void RaysToPMScan(ray_config_t *cfg, ray_measurment_t *src, PMScan *dst)
int RaysToMbICP(ray_config_t *cfg, ray_measurment_t *src, Tpfp *dst, bool test_angle=0, double angle=M_PI/2.2)
Nonholonomic motion model declaration.
TSMparams params
Definition: MbICP.c:103
Generic types declaration for use in the lidar_egomotion algorithm.
void CreateMeasurementFromDisplacement(double dx, double dy, double dtheta, double z[2], double dt, double l, double bwa)
MbICP scan matcher modified main header.
double bwa
#define M_PI
Definition: TData.h:61
pcl::PointCloud< pcl::PointXYZ > wrapper_Laserscan2PointCloud(const sensor_msgs::LaserScan &scan)
void ConvertEstimatedToMeasurment(double vl, double dir, float *dx, float *dy, float *dtheta, double dt, double l, double bwa)
void laser_2_Handler(const sensor_msgs::LaserScan &scan)
void RaysToLDP(ray_definition *src, LDP dst, bool test_angle=0, double angle=M_PI/2.5)
void SetDefaultConfiguration(void)
void laser_3_Handler(const sensor_msgs::LaserScan &scan)
void ConfigurePLICP(struct sm_params *params, LDP ref, LDP sens)
Plplot auxiliary drawing class declaration.
void CleanZone(ray_definition *rays, double steering_angle)
Structure describing a laser scan.
Definition: polar_match.h:128
External polar scan matcher algorithm main header.
Definition: TData.h:74


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