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
00027 #ifndef _c_trajectory_H_
00028 #define _c_trajectory_H_
00029
00038
00039 #include <ros/ros.h>
00040 #include <stdio.h>
00041 #include <vector>
00042 #include <math.h>
00043 #include <visualization_msgs/Marker.h>
00044 #include <visualization_msgs/MarkerArray.h>
00045 #include <tf/transform_listener.h>
00046 #include <pcl_ros/transforms.h>
00047 #include <pcl/ros/conversions.h>
00048 #include <pcl/point_cloud.h>
00049 #include <pcl/point_types.h>
00050 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00051 #include <pcl/filters/extract_indices.h>
00052 #include <pcl/filters/project_inliers.h>
00053 #include <pcl/filters/voxel_grid.h>
00054
00055 typedef enum {SUCCESS, FAILURE}t_func_output;
00056
00057
00058 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__);
00059 #define _USE_MATH_DEFINES
00060 #define _TRAJECTORY_LIB_DEBUG_ 1
00061
00062
00063
00064 using namespace std;
00065
00066 typedef struct{
00067 double width;
00068 double lenght_back;
00069 double lenght_front;
00070 double height_top;
00071 double height_bottom;
00072 }t_vehicle_description;
00073
00074
00075 typedef struct{
00076 double x[2];
00077 double y[2];
00078 }t_lines;
00079
00080
00081 typedef struct{
00082 double x;
00083 double y;
00084 }t_point;
00085
00086 class c_trajectory
00087 {
00088 public:
00089 c_trajectory(double D_in)
00090 {
00091 D = D_in;
00092 #if _TRAJECTORY_LIB_DEBUG_
00093 printf("Constructor - Defining D...\n");
00094 #endif
00095 };
00096
00097 ~c_trajectory()
00098 {
00099 #if _TRAJECTORY_LIB_DEBUG_
00100 printf("Destructor...\n");
00101 #endif
00102 };
00103
00104
00105
00106 vector<vector<t_lines> > v_lines;
00107 vector<t_point> collision_pts;
00108 vector<double> lx;
00109 vector<double> ly;
00110 vector<double> ltheta;
00111 vector<tf::Transform> ltrans;
00112
00113
00114 vector<double> x;
00115 vector<double> y;
00116 vector<double> theta;
00117
00118 struct{
00119 double DAP;
00120 double ADAP;
00121 double DLO;
00122 double DAPnorm;
00123 double ADAPnorm;
00124 double DLOnorm;
00125 double FS;
00126 double overall_norm;
00127 }score;
00128
00129 int closest_node;
00130
00131
00132 vector<double> alpha;
00133 vector<double> arc;
00134 vector<double> speed;
00135 double D;
00136
00137
00138 vector<double> total_arc;
00139
00140
00141 t_func_output generate(vector<double> alpha_in, vector<double> arc_in, vector<double> speed_in, t_vehicle_description& vd);
00142 t_func_output compute_transformation();
00143 void create_markers(std::vector<visualization_msgs::Marker>* marker_vec, int* marker_count, int num_traj);
00144
00145
00146 private:
00147
00148
00149 };
00150 typedef boost::shared_ptr<c_trajectory> c_trajectoryPtr;
00151
00152 #endif