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 #include <trajectory_planner/c_manage_trajectory.h>
00028
00039 t_func_output c_manage_trajectory::compute_DLO(c_trajectoryPtr& trajectory, std::vector<t_obstacle>& vo)
00040 {
00041
00042 trajectory->collision_pts.erase(trajectory->collision_pts.begin(), trajectory->collision_pts.end());
00043
00044 if (trajectory->closest_node<0 || trajectory->closest_node >=(int)trajectory->x.size())
00045 {
00046 ROS_ERROR("Error on node");
00047 return FAILURE;
00048 }
00049
00050
00051 trajectory->score.DLO = 10.0;
00052 trajectory->score.FS = 1;
00053 for (int n=0; n<= trajectory->closest_node; ++n)
00054 {
00055 if (trajectory->v_lines.size()!=trajectory->x.size())
00056 {
00057 ROS_ERROR("Node lines and number of nodes not equal");
00058 }
00059
00060
00061 for (size_t l=0; l< trajectory->v_lines[n].size(); ++l)
00062 {
00063 double Ax = trajectory->v_lines[n][l].x[0];
00064 double Ay = trajectory->v_lines[n][l].y[0];
00065 double Bx = trajectory->v_lines[n][l].x[1];
00066 double By = trajectory->v_lines[n][l].y[1];
00067
00068
00069 for (size_t o=0; o< vo.size(); ++o)
00070 {
00071
00072 for (size_t lo=1; lo< vo[o].x.size(); ++lo)
00073 {
00074 double DLOprev = sqrt(pow(trajectory->v_lines[n][l].x[0]-vo[o].x[lo-1],2)+pow(trajectory->v_lines[n][l].y[0]-vo[o].y[lo-1],2));
00075 if(trajectory->score.DLO > DLOprev)
00076 {
00077 trajectory->score.DLO=DLOprev;
00078 }
00079 double Cx = vo[o].x[lo-1];
00080 double Cy = vo[o].y[lo-1];
00081 double Dx = vo[o].x[lo];
00082 double Dy = vo[o].y[lo];
00083 double X,Y;
00084
00085 int ret = lineSegmentIntersection( Ax, Ay,
00086 Bx, By,
00087 Cx, Cy,
00088 Dx, Dy,
00089 &X, &Y);
00090
00091 if (ret==DO_INTERSECT)
00092 {
00093 t_point p;
00094 p.x=X;
00095 p.y=Y;
00096 trajectory->collision_pts.push_back(p);
00097 trajectory->score.FS*=0;
00098 }
00099 }
00100 }
00101 }
00102 }
00103 return SUCCESS;
00104 }
00105
00121 int c_manage_trajectory::lineSegmentIntersection(double Ax, double Ay,double Bx, double By,double Cx, double Cy,double Dx, double Dy,double *X, double *Y)
00122 {
00123 double distAB, theCos, theSin, newX, ABpos ;
00124
00125
00126 if (((Ax==Bx) && (Ay==By)) || ((Cx==Dx) && (Cy==Dy))) return DONT_INTERSECT;
00127
00128
00129 if (((Ax==Cx) && (Ay==Cy)) || ((Bx==Cx) && (By==Cy))
00130 || ((Ax==Dx) && (Ay==Dy)) || ((Bx==Dx) && (By==Dy))) {
00131 return DONT_INTERSECT; }
00132
00133
00134 Bx-=Ax; By-=Ay;
00135 Cx-=Ax; Cy-=Ay;
00136 Dx-=Ax; Dy-=Ay;
00137
00138
00139 distAB=sqrt(Bx*Bx+By*By);
00140
00141
00142 theCos=Bx/distAB;
00143 theSin=By/distAB;
00144 newX=Cx*theCos+Cy*theSin;
00145 Cy =Cy*theCos-Cx*theSin; Cx=newX;
00146 newX=Dx*theCos+Dy*theSin;
00147 Dy =Dy*theCos-Dx*theSin; Dx=newX;
00148
00149
00150 if ((Cy<0. && Dy<0.) || (Cy>=0. && Dy>=0.)) return DONT_INTERSECT;
00151
00152
00153 ABpos=Dx+(Cx-Dx)*Dy/(Dy-Cy);
00154
00155
00156 if (ABpos<0. || ABpos>distAB) return DONT_INTERSECT;
00157
00158
00159 *X=Ax+ABpos*theCos;
00160 *Y=Ay+ABpos*theSin;
00161
00162
00163 return DO_INTERSECT;
00164 }
00165
00171 t_func_output c_manage_trajectory::set_obstacles(mtt::TargetListPC& msg)
00172 {
00173 vo.erase(vo.begin(), vo.end());
00174 for (size_t i=0; i<msg.obstacle_lines.size(); ++i)
00175 {
00176 t_obstacle o;
00177
00178 pcl::PointCloud<pcl::PointXYZ> pc;
00179 pcl::fromROSMsg(msg.obstacle_lines[i], pc);
00180
00181 for (size_t j=0; j<pc.points.size(); ++j)
00182 {
00183 o.x.push_back(pc.points[j].x);
00184 o.y.push_back(pc.points[j].y);
00185 }
00186
00187 vo.push_back(o);
00188 }
00189 return SUCCESS;
00190 }
00191
00202 t_func_output c_manage_trajectory::set_vehicle_description(double w, double lb, double lf, double ht, double hb)
00203 {
00204 vehicle_description.width = w;
00205 vehicle_description.lenght_back = lb;
00206 vehicle_description.lenght_front = lf;
00207 vehicle_description.height_top = ht;
00208 vehicle_description.height_bottom = hb;
00209 return SUCCESS;
00210 }
00211
00218 t_func_output c_manage_trajectory::get_traj_info_msg_from_chosen(trajectory_planner::traj_info* info)
00219 {
00220 info->arc.erase(info->arc.begin(), info->arc.end());
00221 info->total_arc.erase(info->total_arc.begin(), info->total_arc.end());
00222 info->alpha.erase(info->alpha.begin(), info->alpha.end());
00223 info->speed.erase(info->speed.begin(), info->speed.end());
00224 for(int j=0;j<=(int)vt[chosen_traj.index]->closest_node;++j)
00225 {
00226 info->arc.push_back(vt[chosen_traj.index]->arc[j]);
00227 info->total_arc.push_back(vt[chosen_traj.index]->total_arc[j]);
00228 info->alpha.push_back(vt[chosen_traj.index]->alpha[j]);
00229 }
00230 set_speed_vector(info);
00231
00232 cout<<"ARC SIZE (when constructing) "<<info->arc.size()<<endl;
00233 cout<<"TOTAL ARC SIZE (when constructing) "<<info->total_arc.size()<<endl;
00234 cout<<"ALPHA SIZE (when constructing) "<<info->alpha.size()<<endl;
00235 cout<<"SPEED SIZE (when constructing) "<<info->speed.size()<<endl;
00236 return SUCCESS;
00237 }
00238
00239
00246 t_func_output c_manage_trajectory::set_speed_vector(trajectory_planner::traj_info* info)
00247 {
00248 for(int i=0;i<=(int)vt[chosen_traj.index]->closest_node;++i)
00249 {
00250 if(i < ((int)vt[chosen_traj.index]->arc.size() - 1))
00251 {
00252 if((info->arc[i])*(info->arc[i+1])<0.0)
00253 {
00254 info->speed.push_back((info->arc[i]/fabs(info->arc[i]))*_SPEED_SAFFETY_);
00255 }
00256 else
00257 {
00258 info->speed.push_back((info->arc[i]/fabs(info->arc[i]))*_SPEED_REQUIRED_);
00259 }
00260 }
00261 else
00262 {
00263 info->speed.push_back((info->arc[i]/fabs(info->arc[i]))*_SPEED_REQUIRED_);
00264 }
00265 }
00266 return SUCCESS;
00267 }
00268
00269
00275 int c_manage_trajectory::set_chosen_traj(int n)
00276 {
00277 chosen_traj.index=n;
00278 return 1;
00279 }
00280
00289 t_func_output c_manage_trajectory::set_attractor_point(double x, double y, double theta)
00290 {
00291 AP.x = x; AP.y = y; AP.theta=theta;
00292 return SUCCESS;
00293 }
00294
00301 t_func_output c_manage_trajectory::compute_global_traj_score(c_trajectoryPtr& trajectory)
00302 {
00303 double W_DAP=0.40;
00304 double W_ADAP=0.35;
00305 double W_DLO=0.25;
00306 trajectory->score.overall_norm = (W_DAP*trajectory->score.DAPnorm + W_ADAP*trajectory->score.ADAPnorm + W_DLO*trajectory->score.DLOnorm)*trajectory->score.FS;
00307 cout<<"Overallscore= "<<trajectory->score.overall_norm<<endl;
00308
00309 return SUCCESS;
00310 }
00311
00318 t_func_output c_manage_trajectory::set_inter_axis_distance(double val)
00319 {
00320 inter_axis_distance = val;
00321 return SUCCESS;
00322 }
00323
00331 t_func_output c_manage_trajectory::create_new_trajectory(vector<double> alpha_in, vector<double> arc_in, vector<double> speed_in)
00332 {
00333
00334 c_trajectoryPtr t_ptr(new c_trajectory(inter_axis_distance));
00335 vt.push_back(t_ptr);
00336
00337
00338 return vt[vt.size()-1]->generate(alpha_in, arc_in, speed_in, vehicle_description);
00339 }
00340
00346 t_func_output c_manage_trajectory::compute_chosen_traj(void)
00347 {
00348 double max_val=-1;
00349 chosen_traj.index=-1;
00350
00351 for (int i=0; i< (int)vt.size(); i++)
00352 {
00353 if (vt[i]->score.overall_norm>max_val)
00354 {
00355 chosen_traj.index=i;
00356 max_val= vt[i]->score.overall_norm;
00357 }
00358 }
00359
00360
00361 if(chosen_traj.index!=-1)
00362 return SUCCESS;
00363 else
00364 return FAILURE;
00365 }
00366
00372 t_func_output c_manage_trajectory::create_static_markers(void)
00373 {
00374 cout<<"ja create static"<<endl;
00375 static_marker_vec.clear();
00376 int marker_count=0;
00377 for (int i=0; i< (int)vt.size(); i++)
00378 {
00379 vt[i]->create_markers(&static_marker_vec, &marker_count, i);
00380 }
00381 return SUCCESS;
00382 }
00383
00390 t_func_output c_manage_trajectory::compute_vis_marker_array(visualization_msgs::MarkerArray* marker_array)
00391 {
00392 std::vector<visualization_msgs::Marker> marker_vec;
00393
00394 ROS_INFO("static marker vec size=%ld",static_marker_vec.size());
00395 for(size_t i=0;i<static_marker_vec.size();++i)
00396 {
00397 marker_vec.push_back(static_marker_vec[i]);
00398 }
00399
00400
00401
00402 int marker_count=0;
00403 for (int i=0; i< (int)vt.size(); ++i)
00404 {
00405 draw_on_node(vt[i],&marker_vec,&marker_count,0.15,vt[i]->score.DAP,vt[i]->score.DAPnorm,"DAP ");
00406 draw_on_node(vt[i],&marker_vec,&marker_count,0.30,vt[i]->score.ADAP,vt[i]->score.ADAPnorm,"ADAP ");
00407 draw_on_node(vt[i],&marker_vec,&marker_count,0.45,vt[i]->score.DLO,vt[i]->score.DLOnorm,"DLO ");
00408 draw_on_node(vt[i],&marker_vec,&marker_count,0.60,(vt[i]->score.DAP+vt[i]->score.ADAP+vt[i]->score.DLO)*vt[i]->score.FS,vt[i]->score.overall_norm,"Overall ");
00409 }
00410
00411
00412
00413
00414
00415
00416 visualization_msgs::Marker marker2;
00417 geometry_msgs::Point p;
00418 marker2.header.frame_id = "/parking_frame";
00419 marker2.header.stamp = ros::Time::now();
00420 marker2.ns = "Chosen trajectory";
00421 marker2.id = 0;
00422 marker2.action = visualization_msgs::Marker::ADD;
00423 marker2.type = visualization_msgs::Marker::LINE_LIST;
00424 marker2.scale.x = 0.05;
00425 marker2.color.r = 0.00;
00426 marker2.color.g = 1.00;
00427 marker2.color.b = 0.00;
00428 marker2.color.a = 1.00;
00429 int first_step=1;
00430 for(size_t i=0; i<vt[chosen_traj.index]->x.size(); ++i)
00431 {
00432 if(first_step==1)
00433 {
00434 p.x = 0;
00435 p.y = 0;
00436 p.z = 0.00;
00437 marker2.points.push_back(p);
00438 p.x = vt[chosen_traj.index]->x[i];
00439 p.y = vt[chosen_traj.index]->y[i];
00440 p.z = 0.00;
00441 marker2.points.push_back(p);
00442 first_step=0;
00443 }
00444 else
00445 {
00446 p.x = vt[chosen_traj.index]->x[i-1];
00447 p.y = vt[chosen_traj.index]->y[i-1];
00448 p.z = 0.00;
00449 marker2.points.push_back(p);
00450 p.x = vt[chosen_traj.index]->x[i];
00451 p.y = vt[chosen_traj.index]->y[i];
00452 p.z = 0.00;
00453 marker2.points.push_back(p);
00454 }
00455 }
00456 marker_vec.push_back(marker2);
00457
00458
00459
00460
00461
00462
00463 visualization_msgs::Marker marker;
00464 marker.header.frame_id = "/parking_frame";
00465 marker.header.stamp = ros::Time::now();
00466 marker.ns = "car actual node";
00467 marker.id = 0;
00468 marker.action = visualization_msgs::Marker::ADD;
00469 marker.type = visualization_msgs::Marker::CUBE;
00470 marker.scale.x = 0.8;
00471 marker.scale.y = 0.42;
00472 marker.scale.z = 0.05;
00473 marker.color.r = 0.80;
00474 marker.color.g = 0.50;
00475 marker.color.b = 0.20;
00476 marker.color.a = 0.8;
00477 marker.pose.position.x = vt[chosen_traj.index]->x[current_node]+0.2*cos(vt[chosen_traj.index]->theta[current_node]);
00478 marker.pose.position.y = vt[chosen_traj.index]->y[current_node]+0.2*sin(vt[chosen_traj.index]->theta[current_node]);
00479 marker.pose.position.z = 0;
00480 marker.pose.orientation.z = sin(vt[chosen_traj.index]->theta[current_node]/2);
00481 marker.pose.orientation.w = cos(vt[chosen_traj.index]->theta[current_node]/2);
00482 marker_vec.push_back(marker);
00483
00484
00485
00486
00487
00488
00489
00490 visualization_msgs::Marker marker3;
00491 marker3.header.frame_id = "/parking_frame";
00492 marker3.header.stamp = ros::Time::now();
00493 marker3.ns = "Closest Node";
00494 marker3.action = visualization_msgs::Marker::ADD;
00495 marker3.type = visualization_msgs::Marker::SPHERE;
00496 marker3.scale.x = 0.2;
00497 marker3.scale.y = 0.2;
00498 marker3.scale.z = 0.2;
00499 marker3.color.r = 1.0;
00500 marker3.color.g = 0.0;
00501 marker3.color.b = 0.1;
00502 marker3.color.a = 0.6;
00503
00504 for(size_t i=0; i<vt.size(); ++i)
00505 {
00506 marker3.id +=2;
00507 marker3.pose.position.x = vt[i]->x[vt[i]->closest_node];
00508 marker3.pose.position.y = vt[i]->y[vt[i]->closest_node];
00509 marker3.pose.position.z = 0;
00510 marker_vec.push_back(marker3);
00511 }
00512
00513
00514
00515
00516
00517
00518
00519 visualization_msgs::Marker marker4;
00520 marker4.header.frame_id = "/parking_frame";
00521 marker4.header.stamp = ros::Time::now();
00522 marker4.ns = "Colision points";
00523 marker4.action = visualization_msgs::Marker::ADD;
00524 marker4.type = visualization_msgs::Marker::CYLINDER;
00525 marker4.scale.x = 0.075;
00526 marker4.scale.y = 0.075;
00527 marker4.scale.z = 0.1;
00528 marker4.color.r = 1.0;
00529 marker4.color.g = 0.84;
00530 marker4.color.b = 0.0;
00531 marker4.color.a = 0.6;
00532
00533
00534 static size_t coli_marker_total = 0;
00535 int total=0;
00536 for(size_t j=0; j<vt.size(); ++j)
00537 {
00538 ROS_INFO("Traj%ld has %ld collisions\n",j,vt[j]->collision_pts.size());
00539
00540 for(size_t i=0; i<vt[j]->collision_pts.size(); ++i)
00541 {
00542 marker4.id =total;
00543 marker4.pose.position.x = vt[j]->collision_pts[i].x;
00544 marker4.pose.position.y = vt[j]->collision_pts[i].y;
00545 marker_vec.push_back(marker4);
00546 total++;
00547 }
00548 }
00549
00550 ROS_INFO("total=%d coli=%ld",total,coli_marker_total);
00551
00552 for(size_t j=total; j<coli_marker_total; ++j)
00553 {
00554 ROS_INFO("deleting marker ");
00555 marker4.header.frame_id = "/parking_frame";
00556 marker4.id =j;
00557 marker4.action = visualization_msgs::Marker::DELETE;
00558 marker_vec.push_back(marker4);
00559 }
00560
00561 coli_marker_total = total;
00562
00563
00564 marker_array->markers=marker_vec;
00565
00566 return SUCCESS;
00567 }
00568
00574 t_func_output c_manage_trajectory::compute_trajectories_scores(void)
00575 {
00576
00577 double maximum_admissible_to_DAP=8.0;
00578 double maximum_admissible_to_DLO=10.0;
00579 for (int i=0; i< (int)vt.size(); ++i)
00580 {
00581
00582 compute_DAP(vt[i],AP);
00583
00584
00585 compute_DLO(vt[i], vo);
00586
00587
00588
00589 vt[i]->score.DAPnorm=1-(vt[i]->score.DAP)/maximum_admissible_to_DAP;
00590
00591
00592 vt[i]->score.ADAPnorm=1.0-(vt[i]->score.ADAP/(M_PI));
00593
00594
00595 vt[i]->score.DLOnorm=(vt[i]->score.DLO)/maximum_admissible_to_DLO;
00596 }
00597
00598
00599 for (size_t i=0; i< vt.size(); ++i)
00600 {
00601 compute_global_traj_score(vt[i]);
00602 }
00603
00604 compute_chosen_traj();
00605
00606 return SUCCESS;
00607 }
00608
00616 t_func_output c_manage_trajectory::compute_DAP(c_trajectoryPtr& trajectory,t_desired_coordinates& AP)
00617 {
00618 trajectory->score.DAP=10e6;
00619
00620 trajectory->closest_node=-1;
00621
00622 for(size_t i = 0; i < trajectory->x.size(); ++i)
00623 {
00624 double DAP_prev = sqrt( pow(trajectory->x[i]-AP.x,2)+ pow(trajectory->y[i]-AP.y,2));
00625
00626 if(DAP_prev < trajectory->score.DAP)
00627 {
00628 trajectory->score.DAP = DAP_prev;
00629 trajectory->closest_node = i;
00630 }
00631 }
00632
00633 if(trajectory->closest_node!=-1)
00634 {
00635 trajectory->score.ADAP=compute_ADAP(trajectory,AP,trajectory->closest_node);
00636 return SUCCESS;
00637 }
00638 else
00639 {
00640 return FAILURE;
00641 }
00642 }
00643
00652 double c_manage_trajectory::compute_ADAP(c_trajectoryPtr& trajectory,t_desired_coordinates& AP, int i)
00653 {
00654 double adap=abs(trajectory->theta[i]-AP.theta);
00655 if (adap>M_PI)
00656 adap=2*M_PI-adap;
00657 return adap;
00658 }
00659
00671 void c_manage_trajectory::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)
00672 {
00673
00674 visualization_msgs::Marker marker;
00675 std_msgs::ColorRGBA color;
00676
00677
00678
00679
00680
00681 marker.header.frame_id = "/parking_frame";
00682 marker.header.stamp = ros::Time::now();
00683 marker.ns = "info";
00684 marker.action = visualization_msgs::Marker::ADD;
00685 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00686 marker.pose.orientation.x = 0.0;
00687 marker.pose.orientation.y = 0.0;
00688 marker.pose.orientation.z = 0.0;
00689 marker.pose.orientation.w = 1.0;
00690 marker.scale.z = 0.15;
00691 marker.color.r = 0.80;
00692 marker.color.g = 0.50;
00693 marker.color.b = 0.20;
00694 marker.color.a = 1.0;
00695 marker.id = (*marker_count)++;
00696 marker.pose.position.x = trajectory->x[trajectory->x.size()-1]+0.25+z_high;
00697 marker.pose.position.y = trajectory->y[trajectory->x.size()-1];
00698 marker.pose.position.z = z_high;
00699
00700 marker.text = string_init + str( boost::format("%.2f") % value) + " ("+str( boost::format("%.2f") % normalized_value)+")";
00701 marker_vec->push_back(marker);
00702 }