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_manage_trajectory_H_
00028 #define _c_manage_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 #include <numeric>
00055 #include <trajectory_planner/c_trajectory.h>
00056 #include <mtt/TargetListPC.h>
00057 #include <trajectory_planner/traj_info.h>
00058
00059 typedef struct{
00060
00061 double x;
00062 double y;
00063
00064 double theta;
00065 }t_desired_coordinates;
00066
00067 typedef struct{
00068 std::vector<double> x;
00069 std::vector<double> y;
00070 int id;
00071 }t_obstacle;
00072
00073
00074
00075 #define DONT_INTERSECT 0
00076 #define DO_INTERSECT 1
00077 #define COLLINEAR 2
00078 #define _SPEED_REQUIRED_ 0.25
00079 #define _SPEED_SAFFETY_ 0.05
00080 #define _USE_MATH_DEFINES
00081 #define _TRAJECTORY_LIB_DEBUG_ 1
00082
00083
00084 using namespace std;
00085
00086 class c_manage_trajectory
00087 {
00088 public:
00089 c_manage_trajectory(void)
00090 {
00091 chosen_traj.index=-1;
00092 AP.x=-1.0; AP.y=0.0; AP.theta=M_PI/8;
00093 current_node=0;
00094 #if _TRAJECTORY_LIB_DEBUG_
00095 printf("Constructor...\n");
00096 #endif
00097 };
00098
00099 ~c_manage_trajectory()
00100 {
00101 #if _TRAJECTORY_LIB_DEBUG_
00102 printf("Destructor...\n");
00103 #endif
00104 };
00105
00106
00107 std::vector<c_trajectoryPtr> vt;
00108 t_vehicle_description vehicle_description;
00109 t_desired_coordinates AP;
00110 double inter_axis_distance;
00111 int current_node;
00112 std::vector<visualization_msgs::Marker> static_marker_vec;
00113 std::vector<t_obstacle> vo;
00114 struct{
00115 int index;
00116 }chosen_traj;
00117
00118
00119 t_func_output set_speed_vector(trajectory_planner::traj_info* info);
00120 t_func_output get_traj_info_msg_from_chosen(trajectory_planner::traj_info* info);
00121 t_func_output set_vehicle_description(double w, double lb, double lf, double ht, double hb);
00122 t_func_output set_obstacles(mtt::TargetListPC& msg);
00123 int lineSegmentIntersection(double Ax, double Ay,double Bx, double By,double Cx, double Cy,double Dx, double Dy,double *X, double *Y);
00124 t_func_output compute_DLO(c_trajectoryPtr& trajectory, std::vector<t_obstacle>& vo);
00125 t_func_output compute_trajectories_scores();
00126 t_func_output compute_vis_marker_array(visualization_msgs::MarkerArray* marker_array);
00127 t_func_output create_static_markers();
00128 t_func_output create_new_trajectory(vector<double> alpha_in, vector<double> arc_in, vector<double> speed_in);
00129 t_func_output set_inter_axis_distance(double val);
00130 t_func_output compute_DAP(c_trajectoryPtr& trajectory,t_desired_coordinates& AP);
00131 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);
00132 double compute_ADAP(c_trajectoryPtr& trajectory,t_desired_coordinates& AP, int i);
00133 t_func_output set_attractor_point(double x, double y, double theta);
00134 t_func_output compute_global_traj_score(c_trajectoryPtr& trajectory);
00135 t_func_output compute_chosen_traj();
00136 int set_chosen_traj(int n);
00137
00138 private:
00139
00140 };
00141 typedef boost::shared_ptr<c_manage_trajectory> c_manage_trajectoryPtr;
00142 #endif