00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #include <angles/angles.h>
00011
00012 #include <art/DARPA_rules.h>
00013
00014 #include "navigator_internal.h"
00015 #include "course.h"
00016 #include <art/steering.h>
00017 #include <art_map/coordinates.h>
00018 #include <art_nav/estimate.h>
00019 using art_msgs::ArtVehicle;
00020 using Coordinates::bearing;
00021 using Coordinates::normalize;
00022
00024 #include <art_map/rotate_translate_transform.h>
00025
00026
00027 Course::Course(Navigator *_nav, int _verbose)
00028 {
00029 verbose = _verbose;
00030 nav = _nav;
00031
00032
00033 estimate = &nav->estimate;
00034 navdata = &nav->navdata;
00035 odom = nav->odometry;
00036 order = &nav->order;
00037 pops = nav->pops;
00038 config_ = &nav->config_;
00039
00040
00041 plan.clear();
00042 polygons.clear();
00043
00044 for (unsigned i = 0; i < 2; ++i)
00045 adj_polys[i].clear();
00046 passing_lane = -1;
00047 passed_lane.clear();
00048
00049 last_error=0;
00050
00051 reset();
00052 }
00053
00054
00055
00056
00057
00058
00059
00060 void Course::begin_run_cycle(void)
00061 {
00062 waypoint_checked = false;
00063
00064
00065
00066
00067
00068
00069
00070 if (0 <= (poly_index = pops->getContainingPoly(plan,
00071 MapPose(estimate->pose.pose))))
00072 {
00073
00074
00075 poly_index = pops->getPolyIndex(polygons, plan.at(poly_index));
00076 }
00077 else
00078 {
00079
00080 poly_index = pops->getContainingPoly(polygons,
00081 MapPose(estimate->pose.pose));
00082 }
00083
00084
00085 if (poly_index < 0)
00086 navdata->cur_poly = -1;
00087 else
00088 navdata->cur_poly = polygons.at(poly_index).poly_id;
00089
00090
00091
00092
00093 int limit = art_msgs::Order::N_WAYPTS;
00094 while (ElementID(order->waypt[0].id) != ElementID(navdata->last_waypt)
00095 && --limit > 0)
00096 {
00097 ROS_DEBUG_STREAM("waypoint " << ElementID(order->waypt[1].id).name().str
00098 << " already reached, advance order->waypt[] array");
00099
00100 for (unsigned i = 1; i < art_msgs::Order::N_WAYPTS; ++i)
00101 order->waypt[i-1] = order->waypt[i];
00102 }
00103
00104
00105 for (unsigned i = 0; i < art_msgs::Order::N_WAYPTS; ++i)
00106 ROS_DEBUG("waypt[%u] %s (%.3f,%.3f), E%d G%d L%d P%d S%d X%d Z%d",
00107 i, ElementID(order->waypt[i].id).name().str,
00108 order->waypt[i].mapxy.x,
00109 order->waypt[i].mapxy.y,
00110 (bool) order->waypt[i].is_entry,
00111 (bool) order->waypt[i].is_goal,
00112 (bool) order->waypt[i].is_lane_change,
00113 (bool) order->waypt[i].is_spot,
00114 (bool) order->waypt[i].is_stop,
00115 (bool) order->waypt[i].is_exit,
00116 (bool) order->waypt[i].is_perimeter);
00117 }
00118
00119 void Course::configure()
00120 {
00121
00122 lane_change_secs = config_->lane_change_secs;
00123
00124 heading_change_ratio = config_->heading_change_ratio;
00125 turning_latency = config_->turning_latency;
00126 k_error = config_->turning_offset_tune;
00127 k_theta = config_->turning_heading_tune;
00128
00129 k_int = config_->turning_int_tune;
00130
00131 min_lane_steer_dist = config_->min_lane_steer_dist;
00132 max_speed_for_sharp = config_->max_speed_for_sharp;
00133 spring_lookahead = config_->spring_lookahead;
00134 max_yaw_rate = config_->real_max_yaw_rate;
00135 zone_waypoint_radius = config_->zone_waypoint_radius;
00136
00137 spot_waypoint_radius = config_->spot_waypoint_radius;
00138
00139 #if 0
00140 ros::NodeHandle nh("~");
00141
00142
00143 nh.param("lane_change_secs", lane_change_secs, 2.0);
00144 ROS_INFO("lane change target is %.3f seconds ahead",
00145 lane_change_secs);
00146
00147
00148 nh.param("lane_steer_time", lane_steer_time, 2.0);
00149 ROS_INFO("lane steering time is %.3f seconds", lane_steer_time);
00150
00151 nh.param("heading_change_ratio", heading_change_ratio, 0.75);
00152 ROS_INFO("heading change ratio is %.3f", heading_change_ratio);
00153
00154 nh.param("turning_latency", turning_latency, 1.0);
00155 ROS_INFO("turning latency time is %.3f seconds", 1.0);
00156
00157
00158 nh.param("turning_offset_tune", k_error, 0.5);
00159 ROS_INFO("yaw tuning parameter (offset) is %.3f", k_error);
00160
00161
00162 nh.param("turning_heading_tune", k_theta, sqrt(k_error/2));
00163 ROS_INFO("yaw tuning parameter (heading) is %.3f", k_theta);
00164
00165
00166 nh.param("yaw_ratio", yaw_ratio, 0.75);
00167 ROS_INFO("yaw ratio is %.3f", yaw_ratio);
00168
00169
00170 nh.param("turning_int_tune", k_int, 1.25);
00171 ROS_INFO("yaw tuning parameter (integral) is %.3f", k_int);
00172
00173
00174
00175 nh.param("min_lane_change_dist", min_lane_change_dist,
00176 (double) (DARPA_rules::min_forw_sep_travel
00177 + ArtVehicle::front_bumper_px));
00178 ROS_INFO("minimum lane change distance is %.3f meters",
00179 min_lane_change_dist);
00180
00181
00182
00183 nh.param("min_lane_steer_dist", min_lane_steer_dist,
00184 (double) ArtVehicle::front_bumper_px);
00185 ROS_INFO("minimum lane steering distance is %.3f meters",
00186 min_lane_steer_dist);
00187
00188
00189 nh.param("max_speed_for_sharp", max_speed_for_sharp ,3.0);
00190 ROS_INFO("maximum speed to go full yaw is %.3f m/s", max_speed_for_sharp);
00191
00192
00193 nh.param("spring_lookahead", spring_lookahead, 0.0);
00194 ROS_INFO("spring lookahead distance is %.3f m", spring_lookahead);
00195
00196 nh.param("real_max_yaw_rate", max_yaw_rate, Steering::maximum_yaw);
00197 ROS_INFO("real maximum yaw rate is %.3f (radians/s)", max_yaw_rate);
00198
00199 nh.param("zone_waypoint_radius", zone_waypoint_radius, 1.0);
00200 ROS_INFO("zone waypoint radius is %.3f m", zone_waypoint_radius);
00201
00202 nh.param("zone_perimeter_radius", zone_perimeter_radius, 2.0);
00203 ROS_INFO("zone perimeter radius is %.3f m", zone_perimeter_radius);
00204
00205 nh.param("spot_waypoint_radius", spot_waypoint_radius, 0.5);
00206 ROS_INFO("spot waypoint radius is %.3f m", spot_waypoint_radius);
00207 #endif
00208 }
00209
00220 void Course::desired_heading(pilot_command_t &pcmd, float offset_ratio)
00221 {
00222 if (Epsilon::equal(pcmd.velocity, 0.0))
00223 return;
00224
00225 Polar aim_polar;
00226
00227 float aim_next_heading = 0;
00228 float aim_distance = 0;
00229 bool aim_in_plan = false;
00230 int aim_index = -1;
00231 float used_velocity = estimate->twist.twist.linear.x;
00232 float target_dist = min_lane_steer_dist;
00233
00234 if (plan.empty())
00235 {
00236
00237 if (verbose >= 2)
00238 ART_MSG(5, "no lane data available, steer using waypoints.");
00239 aim_polar = head_for_waypt(target_dist);
00240 aim_distance = aim_polar.range;
00241 aim_next_heading =
00242 normalize(MapPose(estimate->pose.pose).yaw + aim_polar.heading);
00243 }
00244 else
00245 {
00246
00247 aim_index = pops->getPolyIndex(plan, aim_poly);
00248
00249 poly_list_t edge;
00250 pops->add_polys_for_waypts(plan,edge,order->waypt[0].id,
00251 order->waypt[1].id);
00252
00253
00254 int nearby_poly =
00255 pops->getClosestPoly(edge, MapPose(estimate->pose.pose));
00256 if (nearby_poly >= 0)
00257 nearby_poly = pops->getPolyIndex(plan,edge.at(nearby_poly));
00258 else
00259 nearby_poly = pops->getClosestPoly(plan, MapPose(estimate->pose.pose));
00260
00261 if (aim_poly.poly_id != -1
00262 && aim_index >= 0
00263 && aim_index < (int) plan.size() - 1)
00264 {
00265 if (nearby_poly >= 0)
00266 {
00267 int aim_index2 = pops->index_of_downstream_poly
00268 (plan,nearby_poly,target_dist);
00269
00270 if (aim_index2 > aim_index && aim_index2 < (int) plan.size()-1)
00271 {
00272 aim_index = aim_index2;
00273 aim_poly.poly_id = -1;
00274 }
00275 }
00276
00277 aim_distance = Euclidean::DistanceTo(plan.at(aim_index+1).midpoint,
00278 plan.at(aim_index).midpoint);
00279 aim_next_heading = atan2f(plan.at(aim_index+1).midpoint.y-
00280 plan.at(aim_index).midpoint.y,
00281 plan.at(aim_index+1).midpoint.x-
00282 plan.at(aim_index).midpoint.x);
00283
00284 aim_in_plan = true;
00285
00286 ROS_DEBUG("steering down the lane toward polygon %d",
00287 plan.at(aim_index).poly_id);
00288 }
00289 else
00290 {
00291 if (nearby_poly >= 0)
00292 {
00293 ROS_DEBUG("nearby_poly in desired_heading() is %d",
00294 plan.at(nearby_poly).poly_id);
00295
00296
00297
00298 aim_index =
00299 pops->index_of_downstream_poly(plan, nearby_poly,
00300 target_dist);
00301 if (aim_index >= 0 && aim_index < (int)plan.size()-1)
00302 {
00303
00304 aim_distance =
00305 Euclidean::DistanceTo(plan.at(aim_index+1).midpoint,
00306 plan.at(aim_index).midpoint);
00307
00308 aim_next_heading = atan2f(plan.at(aim_index+1).midpoint.y-
00309 plan.at(aim_index).midpoint.y,
00310 plan.at(aim_index+1).midpoint.x-
00311 plan.at(aim_index).midpoint.x);
00312
00313 aim_in_plan = true;
00314
00315 ROS_DEBUG("steering at least %.3fm "
00316 "down the lane toward polygon %d",
00317 target_dist, plan.at(aim_index).poly_id);
00318 }
00319 else
00320 {
00321
00322 ROS_WARN("no polygon at least %.3fm away, "
00323 "steer using waypoints", target_dist);
00324 aim_polar = head_for_waypt(target_dist);
00325
00326 aim_distance = aim_polar.range;
00327 aim_next_heading =
00328 normalize(MapPose(estimate->pose.pose).yaw
00329 + aim_polar.heading);
00330 }
00331 }
00332 else
00333 {
00334
00335
00336
00337 ROS_WARN("no lane data available, steer using waypoints.");
00338 aim_polar = head_for_waypt(target_dist);
00339 aim_distance = aim_polar.range;
00340 aim_next_heading =
00341 normalize (MapPose(estimate->pose.pose).yaw
00342 + aim_polar.heading);
00343 }
00344 }
00345 }
00346
00347
00348 ROS_DEBUG("desired, current positions: (%.3f, %.3f), (%.3f, %.3f, %.3f)",
00349 order->waypt[1].mapxy.x, order->waypt[1].mapxy.y,
00350 estimate->pose.pose.position.x,
00351 estimate->pose.pose.position.y,
00352 MapPose(estimate->pose.pose).yaw);
00353
00354 float full_heading_change =
00355 fabs(normalize(aim_next_heading-MapPose(estimate->pose.pose).yaw));
00356
00357 float max_speed_to_hit_aim =
00358 max_speed_for_change_in_heading(full_heading_change,
00359 aim_distance,
00360 pcmd.velocity,
00361 max_yaw_rate);
00362
00363 pcmd.velocity = fminf(pcmd.velocity,
00364 max_speed_to_hit_aim);
00365
00366
00367
00368 #if 0
00369 if (pcmd.velocity>used_velocity)
00370 used_velocity += fminf(pcmd.velocity-used_velocity,1.0*turning_latency);
00371 else if (pcmd.velocity < used_velocity)
00372 used_velocity-=fminf(used_velocity-pcmd.velocity,1.0*turning_latency);
00373 #endif
00374
00375 #if 1
00376 used_velocity = fmaxf(pcmd.velocity,used_velocity);
00377 #endif
00378
00379 #if 0
00380 used_velocity = fminf(used_velocity,pcmd.velocity);
00381 #endif
00382
00383 if (verbose >= 3)
00384 ART_MSG(8,"Thresholding speed to %.3f m/s",used_velocity);
00385
00386 float spring_yaw;
00387 if (aim_in_plan)
00388 spring_yaw = get_yaw_spring_system(aim_polar, aim_index,
00389 aim_next_heading,
00390 max_yaw_rate, used_velocity,
00391 offset_ratio);
00392 else
00393 spring_yaw = get_yaw_spring_system(aim_polar, -1, aim_next_heading,
00394 max_yaw_rate, used_velocity);
00395
00396 pcmd.yawRate = spring_yaw;
00397
00398 #if 0
00399 if (Epsilon::equal(pcmd.yawRate,max_yaw_rate))
00400 pcmd.velocity = fminf(pcmd.velocity,Steering::steer_speed_min);
00401 #endif
00402
00403 nav->trace_controller("desired_heading", pcmd);
00404 }
00405
00406
00407 float Course::distance_in_plan(const MapPose &from,
00408 const WayPointNode &wp) const
00409 {
00410 if (plan.empty())
00411 return Euclidean::DistanceToWaypt(from, wp);
00412 else return pops->distanceAlongLane(plan, from.map, wp.map);
00413 }
00414
00415
00416 float Course::distance_in_plan(const MapPose &from,
00417 const MapPose &to) const
00418 {
00419 if (plan.empty())
00420 return Euclidean::DistanceTo(from, to);
00421 else return pops->distanceAlongLane(plan, from.map, to.map);
00422 }
00423
00424 float Course::distance_in_plan(const MapPose &from,
00425 const MapXY &to) const
00426 {
00427 if (plan.empty())
00428 return Euclidean::DistanceTo(from.map, to);
00429 else return pops->distanceAlongLane(plan, from.map,to);
00430 }
00431
00432
00433
00434
00435
00436
00437
00438
00439 void Course::end_run_cycle()
00440 {
00441 if (!waypoint_checked)
00442 ROS_WARN("failed to check for way-point reached!");
00443 }
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453 int Course::find_aim_polygon(poly_list_t &lane)
00454 {
00455
00456 poly_list_t edge;
00457 pops->add_polys_for_waypts(lane,edge,order->waypt[0].id,
00458 order->waypt[1].id);
00459
00460
00461 int nearby_poly = pops->getClosestPoly(edge, MapPose(estimate->pose.pose));
00462 if (nearby_poly < 0)
00463 nearby_poly = pops->getClosestPoly(lane, MapPose(estimate->pose.pose));
00464 else
00465 nearby_poly = pops->getPolyIndex(lane,edge.at(nearby_poly));
00466
00467 if (nearby_poly < 0)
00468 return -1;
00469
00470 #if 1
00471 float aim_distance = min_lane_steer_dist;
00472
00473 if (verbose >= 4)
00474 ART_MSG(8, "aim point %.3fm ahead", aim_distance);
00475
00476 return pops->index_of_downstream_poly(lane, nearby_poly, aim_distance);
00477
00478 #else
00479
00480
00481 float lane_distance =
00482 pops->getShortestDistToPoly(MapPose(estimate->pose.pose), lane.at(nearby_poly));
00483
00484 if (Epsilon::equal(lane_distance,0.0))
00485 return -1;
00486
00487 float lane_change_distance_ratio = estimate->vel.x;
00488 float aim_distance;
00489
00490 if (req_max_dist < Infinite::distance)
00491 aim_distance = req_max_dist;
00492 else
00493 {
00494
00495 aim_distance = fminf(lane_distance * lane_change_distance_ratio,
00496 estimate->vel.x * lane_change_secs);
00497 }
00498
00499 float max_pass_distance = ArtVehicle::length*4;
00500
00501
00502 aim_distance = fminf(max_pass_distance,aim_distance);
00503
00504 if (order->waypt[1].is_goal)
00505 {
00506 float way_dist = distance_in_plan(MapPose(estimate->pose.pose), order->waypt[1]);
00507 aim_distance = fminf(aim_distance,way_dist);
00508 }
00509
00510
00511 aim_distance = fmaxf(aim_distance, ArtVehicle::front_bumper_px);
00512
00513 if (verbose >= 4)
00514 ART_MSG(8, "lane is %.3fm away, aim point %.3fm ahead",
00515 lane_distance, aim_distance);
00516
00517 return pops->index_of_downstream_poly(lane, nearby_poly, aim_distance);
00518
00519 #endif
00520 }
00521
00522
00523
00524
00525
00526
00527
00528
00529
00530
00531
00532
00533
00534
00535
00536
00537
00538 bool Course::find_passing_lane(void)
00539 {
00540 ROS_DEBUG("find passing lane around waypoint %s",
00541 ElementID(order->waypt[1].id).name().str);
00542
00543
00544 adj_lane[0] = order->waypt[1].id;
00545 --adj_lane[0].lane;
00546
00547 adj_lane[1] = order->waypt[1].id;
00548 ++adj_lane[1].lane;
00549
00550 #if 1 // more general implementation, experimental
00551
00552 int cur_index = pops->getClosestPoly(plan, MapPose(estimate->pose.pose));
00553 if (cur_index == -1)
00554 {
00555 if (verbose)
00556 ART_MSG(1, "no polygon nearby in plan");
00557 return false;
00558 }
00559 poly cur_poly = plan.at(cur_index);
00560
00561
00562
00563 int left_lane = -1;
00564 int right_lane = -1;
00565 bool adj_forw[2];
00566
00567 for (unsigned i = 0; i < 2; ++i)
00568 {
00569 adj_lane[i].pt = 0;
00570 adj_polys[i].clear();
00571 if (adj_lane[i].lane == 0)
00572 continue;
00573
00574
00575 pops->AddLanePolys(polygons, adj_polys[i], adj_lane[i]);
00576 int this_index =
00577 pops->getClosestPoly(adj_polys[i],
00578 MapXY(order->waypt[1].mapxy));
00579 if (this_index < 0)
00580 continue;
00581
00582
00583 poly this_poly = adj_polys[i].at(this_index);
00584 if (pops->left_of_poly(this_poly, cur_poly))
00585 left_lane = i;
00586 else
00587 right_lane = i;
00588
00589
00590 adj_forw[i] = pops->same_direction(cur_poly, this_poly, HALFPI);
00591 if (!adj_forw[i])
00592 {
00593
00594 adj_polys[i].clear();
00595 pops->AddReverseLanePolys(polygons, adj_polys[i], adj_lane[i]);
00596 }
00597
00598 if (verbose >= 4)
00599 log(adj_lane[i].lane_name().str, adj_polys[i]);
00600 }
00601
00602
00603 if (right_lane >= 0
00604 && adj_forw[right_lane])
00605 passing_lane = right_lane;
00606 else if (left_lane >= 0
00607 && adj_forw[left_lane])
00608 passing_lane = left_lane;
00609 else if (right_lane >= 0)
00610 passing_lane = right_lane;
00611 else if (left_lane >= 0)
00612 passing_lane = left_lane;
00613 else
00614 {
00615 passing_lane = -1;
00616 ROS_DEBUG("no passing lane available for waypoint %s",
00617 ElementID(order->waypt[1].id).name().str);
00618 return false;
00619 }
00620
00621
00622 passing_left = (passing_lane == left_lane);
00623
00624 if (verbose)
00625 ART_MSG(5, "passing lane %s selected, to %s going %s",
00626 adj_lane[passing_lane].lane_name().str,
00627 (passing_left? "left": "right"),
00628 (adj_forw[passing_lane]? "forward": "backward"));
00629
00630 #else // old version
00631
00632 for (unsigned i = 0; i < 2; ++i)
00633 {
00634
00635
00636
00637 adj_lane[i].pt = 0;
00638 adj_polys[i].clear();
00639 if (adj_lane[i].lane > 0)
00640 {
00641 pops->AddReverseLanePolys(polygons, adj_polys[i], adj_lane[i]);
00642 }
00643 if (verbose >= 4)
00644 log(adj_lane[i].lane_name().str, adj_polys[i]);
00645 }
00646
00647
00648 passing_lane = 1;
00649 while (passing_lane >= 0 && adj_polys[passing_lane].empty())
00650 {
00651 --passing_lane;
00652 }
00653
00654
00655
00656 if (passing_lane < 0)
00657 {
00658 if (verbose)
00659 ART_MSG(1, "no passing lane available for waypoint %s",
00660 order->waypt[1].id.name().str);
00661 return false;
00662 }
00663
00664 passing_left = true;
00665
00666 if (verbose)
00667 ART_MSG(5, "passing lane %s selected",
00668 adj_lane[passing_lane].lane_name().str);
00669
00670 #endif
00671
00672 return true;
00673 }
00674
00675
00676
00677
00678
00679
00680
00681
00682
00683 void Course::find_travel_lane(bool rejoin)
00684 {
00685 if (plan_valid())
00686 {
00687 if (verbose >= 4)
00688 ART_MSG(5, "find_travel_lane() plan still valid");
00689 }
00690 else
00691 {
00692
00693 plan.clear();
00694 aim_poly.poly_id = -1;
00695 set_plan_waypts();
00696
00697 if (polygons.size() == 0)
00698 {
00699 if (verbose >= 2)
00700 ART_MSG(5, "find_travel_lane() has no polygons");
00701 return;
00702 }
00703
00704
00705 pops->add_polys_for_waypts(polygons, plan,
00706 order->waypt[0].id, order->waypt[0].id);
00707 if (verbose >= 6) log("debug plan", plan);
00708
00709
00710 for (int i = 1; i < Order::N_WAYPTS; ++i)
00711 {
00712
00713 if (ElementID(order->waypt[i-1].id)
00714 != ElementID(order->waypt[i].id))
00715
00716
00717 pops->add_polys_for_waypts(polygons, plan,
00718 order->waypt[i-1].id,
00719 order->waypt[i].id);
00720
00721 if (order->waypt[i].is_perimeter)
00722 break;
00723 }
00724
00725 if (plan.size() > 1 && verbose >= 6)
00726 {
00727 ART_MSG(7, "plan[0] start, end waypoints are %s, %s, poly_id = %d",
00728 plan.at(0).start_way.name().str,
00729 plan.at(0).end_way.name().str,
00730 plan.at(0).poly_id);
00731 ART_MSG(7, "plan[1] start, end waypoints are %s, %s, poly_id = %d",
00732 plan.at(1).start_way.name().str,
00733 plan.at(1).end_way.name().str,
00734 plan.at(1).poly_id);
00735 }
00736 log("find_travel_lane() plan", plan);
00737 }
00738
00739 new_plan_lanes = false;
00740 aim_poly.poly_id = -1;
00741
00742 if (rejoin)
00743 {
00744
00745
00746
00747
00748
00749
00750
00751
00752
00753
00754
00755
00756
00757 int aim_index = find_aim_polygon(plan);
00758 if (aim_index >= 0)
00759 {
00760
00761 aim_poly = plan.at(aim_index);
00762 if (verbose >= 2)
00763 ART_MSG(5, "aim polygon is %d", aim_poly.poly_id);
00764 }
00765 }
00766 }
00767
00768
00769
00770
00771
00772
00773
00774 Polar Course::head_for_waypt(float target_dist)
00775 {
00776 using Coordinates::MapXY_to_Polar;
00777 Polar aim_polar = MapXY_to_Polar(MapXY(order->waypt[1].mapxy),
00778 *estimate);
00779 if (aim_polar.range < target_dist)
00780 {
00781 if (special_waypt(1))
00782 {
00783
00784
00785 ART_MSG(8, "waypt[1] is a special way-point, keep current heading");
00786 aim_polar.heading=0.0;
00787 }
00788 else if (order->waypt[1].is_perimeter)
00789 {
00790 ART_MSG(8, "waypt[1] is a perimeter point");
00791 aim_polar = MapXY_to_Polar(MapXY(order->waypt[1].mapxy),
00792 *estimate);
00793 if (fabsf(bearing(MapPose(estimate->pose.pose),
00794 MapXY(order->waypt[1].mapxy)))
00795 > HALFPI)
00796 new_waypoint_reached(order->waypt[1].id);
00797 }
00798 else
00799 {
00800
00801 aim_polar = MapXY_to_Polar(MapXY(order->waypt[2].mapxy),
00802 *estimate);
00803 ART_MSG(8, "waypt[1] less than %.3fm away, using waypt[2] instead",
00804 target_dist);
00805
00806 new_waypoint_reached(order->waypt[1].id);
00807 }
00808 }
00809 return aim_polar;
00810 }
00811
00812
00813 Course::direction_t Course::lane_change_direction(void)
00814 {
00815 int w0_index = pops->get_waypoint_index(polygons, order->waypt[0].id);
00816 int w1_index = pops->get_waypoint_index(polygons, order->waypt[1].id);
00817
00818
00819 if (w0_index < 0 || w1_index < 0)
00820 return Straight;
00821
00822 if (pops->left_of_poly(polygons.at(w1_index), polygons.at(w0_index)))
00823 return Left;
00824 else
00825 return Right;
00826 }
00827
00828
00829
00830
00831
00832
00833
00834
00835
00836
00837
00838
00839
00840 bool Course::lane_waypoint_reached(void)
00841 {
00842
00843 waypoint_checked = true;
00844
00845 if (order->waypt[1].is_perimeter)
00846 return zone_perimeter_reached();
00847
00848
00849
00850
00851
00852
00853 if (special_waypt(1))
00854 return false;
00855
00856 #ifdef USE_PATS
00857 ElementID last_way = pops->updateLaneLocation(polygons,
00858 odom->pose,
00859 order->waypt[0],
00860 order->waypt[1]);
00861 if (last_way == order->waypt[1].id)
00862 {
00863 navdata->last_way = last_way;
00864 return true;
00865 }
00866 return false;
00867 #endif
00868
00869 bool found = false;
00870
00871
00872
00873
00874
00875
00876 int w1_index = -1;
00877
00878 w1_index = pops->get_waypoint_index(polygons, order->waypt[1].id);
00879
00880 if (w1_index >= 0)
00881 {
00882
00883
00884 MapPose w1_pose(MapXY(order->waypt[1].mapxy),
00885 pops->PolyHeading(polygons.at(w1_index)));
00886
00887
00888
00889 float bearing_from_w1 = bearing(w1_pose,
00890 MapXY(odom->pose.pose.position));
00891 if (fabsf(bearing_from_w1) < angles::from_degrees(90))
00892 {
00893
00894 ROS_INFO("reached waypoint %s, bearing %.3f radians",
00895 ElementID(order->waypt[1].id).name().str,
00896 bearing_from_w1);
00897 navdata->last_waypt = order->waypt[1].id;
00898 found = true;
00899 }
00900 }
00901
00902
00903 if (!found)
00904 ROS_DEBUG("cur_poly = %d, last_waypt = %s",
00905 navdata->cur_poly,
00906 ElementID(navdata->last_waypt).name().str);
00907 return found;
00908 }
00909
00915 void Course::lanes_message(const art_msgs::ArtLanes &lanes)
00916 {
00917
00918 polygons.resize(lanes.polygons.size());
00919 for (unsigned num = 0; num < lanes.polygons.size(); num++)
00920 polygons.at(num) = lanes.polygons[num];
00921
00922 if (polygons.empty())
00923 ROS_WARN("empty lanes polygon list received!");
00924
00925
00926 new_plan_lanes = true;
00927
00928 log("lanes input:", polygons);
00929 };
00930
00931
00932 void Course::log(const char *str, const poly_list_t &polys)
00933 {
00934 unsigned npolys = polys.size();
00935 if (npolys > 0)
00936 {
00937 if (verbose >= 3)
00938 {
00939 for (unsigned i = 0; i < npolys; ++i)
00940 {
00941 #if 0
00942 if (verbose >= 5)
00943 ART_MSG(8, "polygon[%u] = %d", i, polys.at(i).poly_id);
00944 #endif
00945 unsigned start_seq = i;
00946 while (i+1 < npolys
00947 && abs(polys.at(i+1).poly_id - polys.at(i).poly_id) == 1)
00948 {
00949 #if 0
00950 if (verbose >= 5)
00951 ART_MSG(8, "polygon run from %u (%d) to %u (%d)",
00952 i, polys.at(i).poly_id,
00953 i+1, polys.at(i+1).poly_id);
00954 #endif
00955 ++i;
00956 }
00957 if (start_seq == i)
00958 ART_MSG(8, "%s polygon at %d", str, polys.at(i).poly_id);
00959 else
00960 ART_MSG(8, "%s polygons from %d to %d",
00961 str, polys.at(start_seq).poly_id, polys.at(i).poly_id);
00962 }
00963 }
00964 }
00965 else
00966 {
00967 if (verbose >= 2)
00968 ART_MSG(8, "%s no polygons at all", str);
00969 }
00970 }
00971
00972
00973 bool Course::new_waypts(void)
00974 {
00975 if (saved_replan_num!=order->replan_num)
00976 return true;
00977
00978 for (unsigned i = 0; i < art_msgs::Order::N_WAYPTS; ++i)
00979 if (saved_waypt_id[i] != order->waypt[i].id)
00980 return true;
00981
00982
00983 return false;
00984 }
00985
00986
00987 void Course::reset(void)
00988 {
00989 if (verbose)
00990 ART_MSG(2, "Course class reset()");
00991
00992
00993 start_pass_location = MapPose();
00994
00995
00996 plan.clear();
00997 aim_poly.poly_id = -1;
00998 }
00999
01000
01001 ElementID Course::replan_roadblock(void)
01002 {
01003 saved_replan_num=order->replan_num;
01004
01005
01006 for (unsigned i = 0; i < art_msgs::Order::N_WAYPTS; ++i)
01007 {
01008 saved_waypt_id[i] = order->waypt[i].id;
01009 if (verbose >= 4)
01010 ART_MSG(8, "saved_waypt_id[%u] = %s",
01011 i, saved_waypt_id[i].name().str);
01012 }
01013
01014
01015 int uturn_exit_index =
01016 pops->getClosestPoly(plan,MapPose(estimate->pose.pose));
01017
01018 MapPose exit_pose;
01019 exit_pose.map.x=plan.at(uturn_exit_index).midpoint.x;
01020 exit_pose.map.y=plan.at(uturn_exit_index).midpoint.y;
01021
01022
01023
01024 ElementID reverse_lane =
01025 pops->getReverseLane(polygons,exit_pose);
01026
01027 if (verbose >= 4)
01028 ART_MSG(5,"Replan from lane %s", reverse_lane.lane_name().str);
01029
01030 return reverse_lane;
01031 }
01032
01033
01034 Course::direction_t Course::intersection_direction(void)
01035 {
01036 int w0_index =
01037 pops->getContainingPoly(polygons,
01038 MapXY(order->waypt[0].mapxy));
01039 int w1_index =
01040 pops->getContainingPoly(polygons,
01041 MapXY(order->waypt[1].mapxy));
01042
01043
01044 if (w0_index < 0 || w1_index < 0)
01045 return Straight;
01046
01047 float w0_heading = pops->PolyHeading(polygons.at(w0_index));
01048 float w1_heading = pops->PolyHeading(polygons.at(w1_index));
01049 float heading_change = normalize(w1_heading - w0_heading);
01050
01051 ROS_DEBUG("heading change from waypoint %s to %s is %.3f radians",
01052 ElementID(order->waypt[0].id).name().str,
01053 ElementID(order->waypt[1].id).name().str,
01054 heading_change);
01055
01056 if (fabsf(heading_change) < angles::from_degrees(30))
01057 return Straight;
01058 else if (heading_change > 0.0)
01059 return Left;
01060 else
01061 return Right;
01062 }
01063
01064
01065
01066
01067
01068 float Course::stop_waypt_distance(bool same_lane)
01069 {
01070 for (unsigned i = 1; i < art_msgs::Order::N_WAYPTS; ++i)
01071 {
01072
01073 if (same_lane
01074 && !ElementID(order->waypt[i].id).same_lane(order->waypt[0].id))
01075 break;
01076
01077 if (order->waypt[i].is_stop)
01078 {
01079
01080 int stop_index =
01081 pops->getContainingPoly(polygons,
01082 MapXY(order->waypt[i].mapxy));
01083 if (stop_index < 0)
01084 continue;
01085
01086 stop_poly = polygons.at(stop_index);
01087 stop_waypt = WayPointNode(order->waypt[i]);
01088 float wayptdist = distance_in_plan(MapPose(estimate->pose.pose), stop_waypt);
01089 if (verbose >= 2)
01090 ART_MSG(5, "Stop at waypoint %s is %.3fm away",
01091 stop_waypt.id.name().str, wayptdist);
01092 return wayptdist;
01093 }
01094 }
01095 return Infinite::distance;
01096 }
01097
01098
01099
01100
01101
01102
01103
01104
01105
01106
01107
01108
01109
01110 bool Course::switch_to_passing_lane()
01111 {
01112
01113 int aim_index = find_aim_polygon(adj_polys[passing_lane]);
01114 if (aim_index == -1)
01115 {
01116 if (verbose)
01117 ART_MSG(2, "unable to pass, no polygon near the aiming point");
01118 return false;
01119 }
01120
01121
01122 passed_lane = plan;
01123
01124
01125 plan.clear();
01126 pops->CollectPolys(adj_polys[passing_lane], plan, aim_index);
01127
01128 log("switch_to_passing_lane() plan", plan);
01129 if (plan.empty())
01130 {
01131 if (verbose)
01132 ART_MSG(2, "no polygons in passing lane past aiming point");
01133 return false;
01134 }
01135
01136 aim_poly=plan.at(0);
01137 MapXY aim_poly_midpt = pops->getPolyEdgeMidpoint(aim_poly);
01138 if (verbose >= 2)
01139 ART_MSG(5, "aiming at polygon %d, midpoint (%.3f, %.3f)",
01140 aim_poly.poly_id, aim_poly_midpt.x, aim_poly_midpt.y);
01141
01142 MapXY start_point =
01143 pops->GetClosestPointToLine (pops->midpoint(aim_poly.p1,aim_poly.p4),
01144 pops->midpoint(aim_poly.p2,aim_poly.p3),
01145 MapXY(estimate->pose.pose.position),
01146 true);
01147
01148 start_pass_location.map=start_point;
01149 start_pass_location.yaw=aim_poly.heading;
01150
01151 ART_MSG(1, "passing starts at (%.3f, %.3f)",
01152 start_pass_location.map.x, start_pass_location.map.y);
01153
01154 return true;
01155 }
01156
01157
01158 float Course::uturn_distance(void)
01159 {
01160 int i = uturn_order_index();
01161 if (i < 0)
01162 return Infinite::distance;
01163
01164
01165 int stop_index =
01166 pops->getContainingPoly(polygons,
01167 MapXY(order->waypt[i].mapxy));
01168 if (stop_index < 0)
01169 return Infinite::distance;
01170
01171
01172 stop_poly = polygons.at(stop_index);
01173 stop_waypt = WayPointNode(order->waypt[i]);
01174
01175
01176 float wayptdist = distance_in_plan(MapPose(estimate->pose.pose), stop_waypt);
01177 if (verbose >= 2)
01178 ART_MSG(5, "U-turn at waypoint %s, %.3fm away",
01179 stop_waypt.id.name().str, wayptdist);
01180 return wayptdist;
01181 }
01182
01183
01184
01185
01186
01187
01188 int Course::uturn_order_index(void)
01189 {
01190 for (unsigned i = 1; i < art_msgs::Order::N_WAYPTS-1; ++i)
01191 {
01192
01193 if (!ElementID(order->waypt[i].id).same_lane(ElementID(order->waypt[0].id)))
01194 break;
01195
01196 if (uturn_waypt(i))
01197 return i;
01198 }
01199 return -1;
01200 }
01201
01202
01203 bool Course::uturn_waypt(unsigned windex)
01204 {
01205 if (order->next_uturn < 0)
01206 return false;
01207
01208 return (windex==(unsigned)order->next_uturn);
01209 }
01210
01211
01212
01213
01214
01215
01216
01217
01218
01219 bool Course::zone_waypoint_reached(void)
01220 {
01221 bool found = false;
01222 waypoint_checked = true;
01223
01224
01225 Polar bumper_polar(0.0, ArtVehicle::front_bumper_px);
01226 float distance =
01227 Euclidean::DistanceToWaypt(bumper_polar,
01228 MapPose(estimate->pose.pose),
01229 WayPointNode(order->waypt[1]));
01230
01231 if (distance <= zone_waypoint_radius)
01232 {
01233
01234 ROS_DEBUG("reached zone waypoint %s, distance %.3fm",
01235 ElementID(order->waypt[1].id).name().str, distance);
01236 navdata->last_waypt = order->waypt[1].id;
01237 found = true;
01238 }
01239 else
01240 {
01241 if (verbose >= 5)
01242 ROS_DEBUG("distance to zone waypoint %s is %.3fm",
01243 ElementID(order->waypt[1].id).name().str, distance);
01244 }
01245
01246 return found;
01247 }
01248
01249 bool Course::zone_perimeter_reached(void)
01250 {
01251 bool found = false;
01252 waypoint_checked = true;
01253
01254 int w1_index =
01255 pops->getClosestPoly(polygons,
01256 MapXY(order->waypt[1].mapxy));
01257 if (w1_index >= 0)
01258 {
01259
01260
01261 MapPose w1_pose(order->waypt[1].mapxy,
01262 pops->PolyHeading(polygons.at(w1_index)));
01263
01264 #if 1
01265
01266
01267 float bearing_from_w1 =
01268 bearing(w1_pose, MapXY(odom->pose.pose.position));
01269 #else // experimental code -- not working right yet
01270
01271
01272 Polar bumper_polar(0.0,
01273 (ArtVehicle::front_bumper_px
01274 + DARPA_rules::stop_line_to_bumper));
01275 MapXY bumper_pos = Polar_to_MapXY(bumper_polar, odom->pos);
01276 float bearing_from_w1 = bearing(w1_pose, bumper_pos);
01277 #endif
01278 if (fabsf(bearing_from_w1) < angles::from_degrees(90))
01279 {
01280
01281 ROS_DEBUG("reached waypoint %s, bearing %.3f radians",
01282 ElementID(order->waypt[1].id).name().str,
01283 bearing_from_w1);
01284 navdata->last_waypt = order->waypt[1].id;
01285 found = true;
01286 }
01287 }
01288
01289 return found;
01290 }
01291
01292
01293 bool Course::spot_waypoint_reached(void)
01294 {
01295 bool found = false;
01296 waypoint_checked = true;
01297
01298
01299 Polar bumper_polar(0.0, ArtVehicle::front_bumper_px);
01300 float distance =
01301 Euclidean::DistanceToWaypt(bumper_polar, MapPose(estimate->pose.pose),
01302 WayPointNode(order->waypt[1]));
01303
01304 if (distance <= spot_waypoint_radius)
01305 {
01306
01307 ROS_DEBUG("reached spot waypoint %s, distance %.3fm",
01308 ElementID(order->waypt[1].id).name().str, distance);
01309 navdata->last_waypt = order->waypt[1].id;
01310 found = true;
01311 }
01312 else
01313 {
01314 if (verbose >= 5)
01315 ROS_DEBUG("distance to spot waypoint %s is %.3fm",
01316 ElementID(order->waypt[1].id).name().str, distance);
01317 }
01318
01319 return found;
01320 }
01321
01322 float Course::max_speed_for_slow_down(const float& final_speed,
01323 const float& distance,
01324 const float& max,
01325 const float& max_deceleration) {
01326
01327
01328
01329
01330
01331
01332
01333
01334
01335
01336 float vf2 = final_speed * final_speed;
01337 float tax = 2 * (-max_deceleration) * distance;
01338
01339
01340 if(tax > vf2)
01341 return 0.0;
01342
01343 return fminf(max, sqrtf(vf2 - tax));
01344 }
01345
01346 float Course::max_speed_for_change_in_heading(const float& dheading,
01347 const float& distance,
01348 const float& max,
01349 const float& maximum_yaw_rate) {
01350
01351
01352
01353
01354
01355
01356
01357 if(Epsilon::equal(dheading,0))
01358 return max;
01359 else
01360 {
01361 float new_speed=fminf(max, fmaxf(max_speed_for_sharp,fabsf(heading_change_ratio * (maximum_yaw_rate / dheading))));
01362 if (verbose>=5)
01363 ART_MSG(3,"slow for heading: distance: %.3f, dheading: %.3f, maximum_yaw_rate: %.3f, max_speed: %.3f, final: %.3f",distance,dheading,maximum_yaw_rate,max,new_speed);
01364 return new_speed;
01365 }
01366 }
01367
01368
01369 float Course::get_yaw_spring_system(const Polar& aim_polar,
01370 int poly_id,
01371 float poly_heading,
01372 float max_yaw,
01373 float curr_velocity,
01374 float offset_ratio)
01375 {
01376 float error = 0;
01377 float theta=-aim_polar.heading;
01378 float velocity = fmaxf(curr_velocity, Steering::steer_speed_min);
01379 nav_msgs::Odometry front_est;
01380 Estimate::front_axle_pose(*estimate, front_est);
01381 ros::Duration frequency(1.0 / art_msgs::ArtHertz::NAVIGATOR);
01382 ros::Time time_in_future = (ros::Time::now()
01383 + frequency
01384 + ros::Duration(velocity * spring_lookahead));
01385 nav_msgs::Odometry pos_est;
01386 Estimate::control_pose(front_est, time_in_future, pos_est);
01387
01388 if (poly_id >=0)
01389 {
01390 poly current_poly=plan.at(poly_id);
01391 posetype origin;
01392 posetype cpoly(current_poly.midpoint.x, current_poly.midpoint.y,
01393 poly_heading);
01394 rotate_translate_transform trans;
01395 trans.find_transform(cpoly,origin);
01396 posetype car(pos_est.pose.pose.position.x,
01397 pos_est.pose.pose.position.y,
01398 0.0);
01399 posetype car_rel=trans.apply_transform(car);
01400
01401 float width=Euclidean::DistanceTo(current_poly.p2,current_poly.p3);
01402
01403
01404 error=car_rel.y;
01405
01406
01407 #if 1 // still experimental:
01408
01409 if (!Epsilon::equal(offset_ratio, 0.0))
01410 {
01411
01412
01413
01414
01415 MapXY mid_left_side =
01416 pops->midpoint(current_poly.p1, current_poly.p2);
01417 float half_lane_width =
01418 Euclidean::DistanceTo(current_poly.midpoint, mid_left_side);
01419 float lane_space = half_lane_width - ArtVehicle::halfwidth;
01420 float error_offset = 0.0;
01421 if (lane_space > 0.0)
01422 error_offset = offset_ratio * lane_space;
01423 if (verbose >= 3)
01424 ART_MSG(8, "error offset %.3f, half lane width %.3f, ratio %.3f",
01425 error_offset, half_lane_width, offset_ratio);
01426
01427
01428 error -= error_offset;
01429 }
01430 #endif
01431 error=fminf(fmaxf(-width,error),width);
01432
01433 theta = normalize(MapPose(pos_est.pose.pose).yaw - poly_heading);
01434 }
01435
01436
01437 float cth = cosf(theta);
01438
01439 float vcth = velocity*cth;
01440
01441 if (fabsf(theta) >= HALFPI ||
01442 Epsilon::equal(cth,0.0) ||
01443 Epsilon::equal(vcth,0.0))
01444 {
01445 ART_MSG(8,"Spring system does not apply: heading offset %.3f", theta);
01446 if (Epsilon::equal(error,0)) {
01447 if (theta < 0)
01448 return max_yaw;
01449 else return -max_yaw;
01450 }
01451 else {
01452 if (error > 0)
01453 return max_yaw;
01454 else return -max_yaw;
01455 }
01456 }
01457
01458 float d2=-k_theta*sinf(theta)/cth;
01459 float d1=-k_error*error/vcth;
01460
01461
01462
01463
01464
01465
01466
01467
01468
01469
01470 if ((Coordinates::sign(error) == Coordinates::sign(last_error)) &&
01471 (fabsf(error) > fabs(last_error)))
01472 d1*=k_int;
01473
01474 last_error=error;
01475 float yaw=d1+d2;
01476
01477 if (verbose >=3)
01478 ART_MSG(8,"Heading spring systems values: error %.3f, dtheta %.3f, d1 %.3f, d2 %.3f, d1+d2 %.3f",error,theta,d1,d2,yaw);
01479
01480 if (yaw < 0)
01481 return fmaxf(-max_yaw, yaw);
01482 return fminf(max_yaw, yaw);
01483 }
01484
01485
01486 bool Course::spot_ahead()
01487 {
01488 for (uint i=0; i<art_msgs::Order::N_WAYPTS-1;i++)
01489 if (order->waypt[i].is_spot &&
01490 order->waypt[i+1].is_spot &&
01491 order->waypt[i].id.pt==1 &&
01492 order->waypt[i+1].id.pt==2)
01493 return true;
01494
01495 return false;
01496
01497 }
01498
01499 bool Course::curr_spot()
01500 {
01501 return order->waypt[0].is_spot;
01502 }
01503
01504 #if 0
01505 mapxy_list_t Course::calculate_zone_barrier_points()
01506 {
01507 mapxy_list_t spot_points;
01508
01509 return spot_points;
01510
01511 if (order->waypt[1].is_spot)
01512 return spot_points;
01513
01514 posetype way_pose(order->waypt[1].mapxy.x,
01515 order->waypt[1].mapxy.y,
01516 atan2f(order->waypt[2].mapxy.y-order->waypt[1].mapxy.y,
01517 order->waypt[2].mapxy.x-order->waypt[1].mapxy.x));
01518
01519 rotate_translate_transform trans;
01520 trans.find_transform(posetype(),way_pose);
01521
01522 posetype npose;
01523 npose=trans.apply_transform(posetype(1,order->waypt[1].lane_width,0));
01524 spot_points.push_back(npose);
01525
01526 npose=trans.apply_transform(posetype(1,order->waypt[1].lane_width/2,0));
01527 spot_points.push_back(npose);
01528
01529 npose=trans.apply_transform(posetype(1,0,0));
01530 spot_points.push_back(npose);
01531
01532 npose=trans.apply_transform(posetype(1,-order->waypt[1].lane_width/2,0));
01533 spot_points.push_back(npose);
01534
01535 npose=trans.apply_transform(posetype(1,-order->waypt[1].lane_width,0));
01536 spot_points.push_back(npose);
01537
01538 return spot_points;
01539 }
01540
01541 mapxy_list_t Course::calculate_spot_points(const std::vector<WayPointNode>& new_waypts)
01542 {
01543 mapxy_list_t spot_points;
01544
01545 for (uint i=0; i<art_msgs::Order::N_WAYPTS-1;i++)
01546 if (new_waypts[i].is_spot &&
01547 new_waypts[i+1].is_spot &&
01548 new_waypts[i].id.pt==1 &&
01549 new_waypts[i+1].id.pt==2)
01550 {
01551 posetype way_pose(new_waypts[i].map.x,new_waypts[i].map.y,
01552 atan2f(new_waypts[i+1].map.y-new_waypts[i].map.y,
01553 new_waypts[i+1].map.x-new_waypts[i].map.x));
01554
01555 float dist=Euclidean::DistanceTo(new_waypts[i+1].map,
01556 new_waypts[i].map);
01557 rotate_translate_transform trans;
01558 trans.find_transform(posetype(),way_pose);
01559
01560 posetype npose;
01561
01562 npose=trans.apply_transform(posetype(0,new_waypts[i].lane_width/2,0));
01563 spot_points.push_back(npose);
01564
01565 npose=trans.apply_transform(posetype(dist,new_waypts[i].lane_width/2,0));
01566 spot_points.push_back(npose);
01567
01568 npose=trans.apply_transform(posetype(dist+2,new_waypts[i].lane_width,0));
01569 spot_points.push_back(npose);
01570
01571 npose=trans.apply_transform(posetype(dist+2,new_waypts[i].lane_width/2,0));
01572 spot_points.push_back(npose);
01573
01574 npose=trans.apply_transform(posetype(dist+2,0,0));
01575 spot_points.push_back(npose);
01576
01577 npose=trans.apply_transform(posetype(dist+2,-new_waypts[i].lane_width/2,0));
01578 spot_points.push_back(npose);
01579
01580 npose=trans.apply_transform(posetype(dist+2,new_waypts[i].lane_width/2,0));
01581 spot_points.push_back(npose);
01582
01583 npose=trans.apply_transform(posetype(dist,-new_waypts[i].lane_width/2,0));
01584 spot_points.push_back(npose);
01585
01586 npose=trans.apply_transform(posetype(0,-new_waypts[i].lane_width/2,0));
01587 spot_points.push_back(npose);
01588
01589 }
01590 return spot_points;
01591 }
01592
01593 mapxy_list_t Course::calculate_spot_points()
01594 {
01595 mapxy_list_t spot_points;
01596
01597 for (uint i=0; i<art_msgs::Order::N_WAYPTS-1;i++)
01598 if (order->waypt[i].is_spot &&
01599 order->waypt[i+1].is_spot &&
01600 order->waypt[i].id.pt==1 &&
01601 order->waypt[i+1].id.pt==2)
01602 {
01603 posetype way_pose(order->waypt[i].mapxy.x,
01604 order->waypt[i].mapxy.y,
01605 atan2f(order->waypt[i+1].mapxy.y-order->waypt[i].mapxy.y,
01606 order->waypt[i+1].mapxy.x-order->waypt[i].mapxy.x));
01607
01608 float dist=Euclidean::DistanceTo(order->waypt[i+1].mapxy,
01609 order->waypt[i].mapxy);
01610 rotate_translate_transform trans;
01611 trans.find_transform(posetype(),way_pose);
01612
01613 posetype npose;
01614
01615 npose=trans.apply_transform(posetype(0,order->waypt[i].lane_width/2,0));
01616 spot_points.push_back(npose);
01617
01618 npose=trans.apply_transform(posetype(dist,order->waypt[i].lane_width/2,0));
01619 spot_points.push_back(npose);
01620
01621 npose=trans.apply_transform(posetype(dist+2,order->waypt[i].lane_width,0));
01622 spot_points.push_back(npose);
01623
01624 npose=trans.apply_transform(posetype(dist+2,order->waypt[i].lane_width/2,0));
01625 spot_points.push_back(npose);
01626
01627 npose=trans.apply_transform(posetype(dist+2,0,0));
01628 spot_points.push_back(npose);
01629
01630 npose=trans.apply_transform(posetype(dist+2,-order->waypt[i].lane_width/2,0));
01631 spot_points.push_back(npose);
01632
01633 npose=trans.apply_transform(posetype(dist+2,order->waypt[i].lane_width/2,0));
01634 spot_points.push_back(npose);
01635
01636 npose=trans.apply_transform(posetype(dist,-order->waypt[i].lane_width/2,0));
01637 spot_points.push_back(npose);
01638
01639 npose=trans.apply_transform(posetype(0,-order->waypt[i].lane_width/2,0));
01640 spot_points.push_back(npose);
01641
01642 }
01643 return spot_points;
01644 }
01645 #endif
01646
01647 bool Course::nqe_special(int i, int j)
01648 {
01649 #ifdef NQE
01650
01651 typedef struct {
01652 ElementID start;
01653 ElementID end;
01654 } id_pair;
01655
01656 static int num_pair=8;
01657
01658 static id_pair id_table[]=
01659 {
01660
01661 {ElementID(1,1,6),ElementID(41,1,1)},
01662 {ElementID(1,2,5),ElementID(41,2,1)},
01663 {ElementID(41,1,7),ElementID(1,1,1)},
01664 {ElementID(41,2,7),ElementID(1,2,1)},
01665
01666 {ElementID(6,1,10),ElementID(5,1,1)},
01667 {ElementID(5,1,7),ElementID(6,1,1)},
01668 {ElementID(6,1,4),ElementID(8,2,1)},
01669 {ElementID(6,1,6),ElementID(7,1,1)},
01670 };
01671
01672 for (int k=0; k< num_pair; k++)
01673 if (order->waypt[i].id==id_table[k].start &&
01674 order->waypt[j].id==id_table[k].end)
01675 return true;
01676 #endif
01677
01678 return false;
01679
01680 }