c_manage_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_manage_trajectory_H_
28 #define _c_manage_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 #include <numeric>
56 #include <mtt/TargetListPC.h>
57 #include <trajectory_planner/traj_info.h>
58 #include <pcl_conversions/pcl_conversions.h>
59 
60 typedef struct{
61  // Positions
62  double x;
63  double y;
64  // Orientation
65  double theta;
67 
68 typedef struct{
69  std::vector<double> x;
70  std::vector<double> y;
71  int id;
72 }t_obstacle;
73 
74 
75 //Defines
76 #define DONT_INTERSECT 0
77 #define DO_INTERSECT 1
78 #define COLLINEAR 2
79 #define _SPEED_REQUIRED_ 0.25
80 #define _SPEED_SAFFETY_ 0.05
81 #define _USE_MATH_DEFINES
82 #define _TRAJECTORY_LIB_DEBUG_ 1
83 
84 // Namespaces
85 using namespace std;
86 
88 {
89  public:
91  {
92  chosen_traj.index=-1;
93  AP.x=-1.0; AP.y=0.0; AP.theta=M_PI/8;
94  current_node=0;
95 #if _TRAJECTORY_LIB_DEBUG_
96  printf("Constructor...\n");
97 #endif
98  };
99 
101  {
102 #if _TRAJECTORY_LIB_DEBUG_
103  printf("Destructor...\n");
104 #endif
105  };
106 
107  // ----- Variables ------
108  std::vector<c_trajectoryPtr> vt; //the traj vector
113  std::vector<visualization_msgs::Marker> static_marker_vec;
114  std::vector<t_obstacle> vo;
115  struct{
116  int index;
117  }chosen_traj;
118 
119  // ------ Functions ------
120  t_func_output set_speed_vector(trajectory_planner::traj_info* info);
121  t_func_output get_traj_info_msg_from_chosen(trajectory_planner::traj_info* info);
122  t_func_output set_vehicle_description(double w, double lb, double lf, double ht, double hb);
123  t_func_output set_obstacles(mtt::TargetListPC& msg);
124  int lineSegmentIntersection(double Ax, double Ay,double Bx, double By,double Cx, double Cy,double Dx, double Dy,double *X, double *Y);
125  t_func_output compute_DLO(c_trajectoryPtr& trajectory, std::vector<t_obstacle>& vo);
126  t_func_output compute_trajectories_scores();
127  t_func_output compute_vis_marker_array(visualization_msgs::MarkerArray* marker_array);
128  t_func_output create_static_markers();
129  t_func_output create_new_trajectory(vector<double> alpha_in, vector<double> arc_in, vector<double> speed_in);
130  t_func_output set_inter_axis_distance(double val);
131  t_func_output compute_DAP(c_trajectoryPtr& trajectory,t_desired_coordinates& AP);
132  void draw_on_node(c_trajectoryPtr& trajectory,std::vector<visualization_msgs::Marker>* marker_vec, int* marker_count,double z_high, double value, double normalized_value, string string_init);
133  double compute_ADAP(c_trajectoryPtr& trajectory,t_desired_coordinates& AP, int i);
134  t_func_output set_attractor_point(double x, double y, double theta);
135  t_func_output compute_global_traj_score(c_trajectoryPtr& trajectory);
136  t_func_output compute_chosen_traj();
137  int set_chosen_traj(int n);
138 
139  private:
140 
141 };
142 typedef boost::shared_ptr<c_manage_trajectory> c_manage_trajectoryPtr;
143 #endif
vector< double > set_speed_vector(boost::shared_ptr< c_trajectory > t)
Determine the speed vector.
boost::shared_ptr< c_trajectory > c_trajectoryPtr
Definition: c_trajectory.h:150
class which generates a few number of trajectories from an input file
t_desired_coordinates AP
trajectory_planner::traj_info info
boost::shared_ptr< c_manage_trajectory > c_manage_trajectoryPtr
std::vector< visualization_msgs::Marker > static_marker_vec
std::vector< t_obstacle > vo
std::vector< double > y
t_vehicle_description vehicle_description
t_func_output
Definition: c_trajectory.h:55
std::vector< double > x


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