c_trajectory.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 ***************************************************************************************************/
27 #ifndef _c_trajectory_H_
28 #define _c_trajectory_H_
29 
38 //INCLUDES
39 #include <ros/ros.h>
40 #include <stdio.h>
41 #include <vector>
42 #include <math.h>
43 #include <visualization_msgs/Marker.h>
44 #include <visualization_msgs/MarkerArray.h>
45 #include <tf/transform_listener.h>
46 #include <pcl_ros/transforms.h>
47 #include <pcl/conversions.h>
48 #include <pcl/point_cloud.h>
49 #include <pcl/point_types.h>
50 #include <pcl/segmentation/extract_polygonal_prism_data.h>
51 #include <pcl/filters/extract_indices.h>
52 #include <pcl/filters/project_inliers.h>
53 #include <pcl/filters/voxel_grid.h>
54 
55 typedef enum {SUCCESS, FAILURE}t_func_output;
56 
57 //Defines
58 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__);
59 #define _USE_MATH_DEFINES
60 #define _TRAJECTORY_LIB_DEBUG_ 1
61 
62 
63 // Namespaces
64 using namespace std;
65 
66 typedef struct{
67 double width;
68 double lenght_back;
69 double lenght_front;
70 double height_top;
73 
74 
75 typedef struct{
76  double x[2];
77  double y[2];
78 }t_lines;
79 
80 
81 typedef struct{
82  double x;
83  double y;
84 }t_point;
85 
87 {
88  public:
89  c_trajectory(double D_in)
90  {
91  D = D_in;
92  #if _TRAJECTORY_LIB_DEBUG_
93  printf("Constructor - Defining D...\n");
94  #endif
95  };
96 
98  {
99  #if _TRAJECTORY_LIB_DEBUG_
100  printf("Destructor...\n");
101  #endif
102  };
103 
104  // ----- Variables ------
105  // Local coordinates
106  vector<vector<t_lines> > v_lines;
107  vector<t_point> collision_pts;
108  vector<double> lx;
109  vector<double> ly;
110  vector<double> ltheta;
111  vector<tf::Transform> ltrans;
112 
113  // Global coordinates
114  vector<double> x;
115  vector<double> y;
116  vector<double> theta;
117 
118  struct{
119  double DAP; //distance to application point
120  double ADAP; //angular difference related to the application point
121  double DLO;
122  double DAPnorm; // normalized
123  double ADAPnorm; // normalized
124  double DLOnorm;
125  double FS;
126  double overall_norm;
127  }score;
128 
130 
131  // Input parameters
132  vector<double> alpha;
133  vector<double> arc;
134  vector<double> speed;
135  double D;
136 
137  // Other paramenters
138  vector<double> total_arc;
139 
140  // ------ Functions ------
141  t_func_output generate(vector<double> alpha_in, vector<double> arc_in, vector<double> speed_in, t_vehicle_description& vd);
142  t_func_output compute_transformation();
143  void create_markers(std::vector<visualization_msgs::Marker>* marker_vec, int* marker_count, int num_traj);
144 
145 
146  private:
147 
148 
149 };
150 typedef boost::shared_ptr<c_trajectory> c_trajectoryPtr;
151 
152 #endif
vector< double > y
Definition: c_trajectory.h:115
vector< double > total_arc
Definition: c_trajectory.h:138
boost::shared_ptr< c_trajectory > c_trajectoryPtr
Definition: c_trajectory.h:150
vector< double > speed
Definition: c_trajectory.h:134
vector< tf::Transform > ltrans
Definition: c_trajectory.h:111
double overall_norm
Definition: c_trajectory.h:126
vector< double > x
Definition: c_trajectory.h:114
double DLOnorm
Definition: c_trajectory.h:124
double DAPnorm
Definition: c_trajectory.h:122
vector< double > ly
Definition: c_trajectory.h:109
vector< double > theta
Definition: c_trajectory.h:116
double x
Definition: c_trajectory.h:82
double ADAPnorm
Definition: c_trajectory.h:123
vector< double > arc
Definition: c_trajectory.h:133
vector< double > lx
Definition: c_trajectory.h:108
c_trajectory(double D_in)
Definition: c_trajectory.h:89
double y
Definition: c_trajectory.h:83
vector< t_point > collision_pts
Definition: c_trajectory.h:107
vector< double > ltheta
Definition: c_trajectory.h:110
t_func_output
Definition: c_trajectory.h:55
vector< double > alpha
Definition: c_trajectory.h:132


trajectory_planner
Author(s): Joel Pereira
autogenerated on Mon Mar 2 2015 01:32:54