$search
00001 /* 00002 * Navigator course planning class 00003 * 00004 * Copyright (C) 2007, 2010, Austin Robot Technology 00005 * License: Modified BSD Software License Agreement 00006 * 00007 * $Id: course.cc 1856 2011-11-18 00:39:09Z jack.oquin $ 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 // Constructor 00027 Course::Course(Navigator *_nav, int _verbose) 00028 { 00029 verbose = _verbose; 00030 nav = _nav; 00031 00032 // copy convenience pointers to Navigator class data 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 // initialize polygon vectors 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 // Course class initialization for run state cycle. 00055 // 00056 // exit: 00057 // navdata->cur_poly updated 00058 // order->waypt array reflects last_waypt 00059 // 00060 void Course::begin_run_cycle(void) 00061 { 00062 waypoint_checked = false; 00063 00064 // Finding the current polygon is easy in a travel lane, but 00065 // more difficult in intersections. They have many overlapping 00066 // transition lanes, and getContainingPoly() picks the first one 00067 // in the polygons vector, not necessarily the correct one. 00068 00069 // So, first check whether vehicle is in the planned travel lane 00070 if (0 <= (poly_index = pops->getContainingPoly(plan, 00071 MapPose(estimate->pose.pose)))) 00072 { 00073 // This is the normal case. Re-resolve poly_index relative to 00074 // polygons vector. 00075 poly_index = pops->getPolyIndex(polygons, plan.at(poly_index)); 00076 } 00077 else 00078 { 00079 // Not in the planned travel lane, check the whole road network. 00080 poly_index = pops->getContainingPoly(polygons, 00081 MapPose(estimate->pose.pose)); 00082 } 00083 00084 // set cur_poly ID in navdata for Commander (no longer used) 00085 if (poly_index < 0) // no polygon found? 00086 navdata->cur_poly = -1; // outside the road network 00087 else 00088 navdata->cur_poly = polygons.at(poly_index).poly_id; 00089 00090 // This order may have been issued before Commander saw the 00091 // last_waypt Navigator returned in a previous cycle. Make sure the 00092 // order reflects the current situation. 00093 int limit = art_msgs::Order::N_WAYPTS; // search limit 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 // advance order->waypt array by one 00100 for (unsigned i = 1; i < art_msgs::Order::N_WAYPTS; ++i) 00101 order->waypt[i-1] = order->waypt[i]; 00102 } 00103 00104 // log current order attributes 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 // dynamic reconfigure parameters 00122 lane_change_secs = config_->lane_change_secs; 00123 //lane_steer_time = config_->lane_steer_time; 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 //yaw_ratio = config_->yaw_ratio; 00129 k_int = config_->turning_int_tune; 00130 //min_lane_change_dist = config_->min_lane_change_dist; 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 //zone_perimeter_radius = config_->zone_perimeter_radius; 00137 spot_waypoint_radius = config_->spot_waypoint_radius; 00138 00139 #if 0 00140 ros::NodeHandle nh("~"); 00141 00142 // how far away (in seconds) we aim when changing lanes 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 // Look-ahead time for steering towards a polygon. 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 // Look-ahead time for steering towards a polygon. 00158 nh.param("turning_offset_tune", k_error, 0.5); 00159 ROS_INFO("yaw tuning parameter (offset) is %.3f", k_error); 00160 00161 // Look-ahead time for steering towards a polygon. 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 // Look-ahead time for steering towards a polygon. 00166 nh.param("yaw_ratio", yaw_ratio, 0.75); 00167 ROS_INFO("yaw ratio is %.3f", yaw_ratio); 00168 00169 // Look-ahead time for steering towards a polygon. 00170 nh.param("turning_int_tune", k_int, 1.25); 00171 ROS_INFO("yaw tuning parameter (integral) is %.3f", k_int); 00172 00173 // Minimum distance to aim for when changing lanes. 00174 // Should at least include front bumper offset and minimum separation. 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 // Minimum look-ahead distance for steering towards a polygon. 00182 // Should at least include front bumper offset. 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 // how fast the maximum steer can be done 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 // how far in future to estimate for reactive steering 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; // egocentric polar aim point 00226 // float aim_abs_heading = 0; 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 // no plan available: a big problem, but must do something 00237 ROS_WARN_THROTTLE(40, "no lane data available, steer using waypoints."); 00238 aim_polar = head_for_waypt(target_dist); 00239 aim_distance = aim_polar.range; 00240 aim_next_heading = 00241 normalize(MapPose(estimate->pose.pose).yaw + aim_polar.heading); 00242 } 00243 else 00244 { 00245 // Look in plan 00246 aim_index = pops->getPolyIndex(plan, aim_poly); 00247 00248 poly_list_t edge; 00249 pops->add_polys_for_waypts(plan,edge,order->waypt[0].id, 00250 order->waypt[1].id); 00251 00252 // get closest polygon to estimated position 00253 int nearby_poly = 00254 pops->getClosestPoly(edge, MapPose(estimate->pose.pose)); 00255 if (nearby_poly >= 0) 00256 nearby_poly = pops->getPolyIndex(plan,edge.at(nearby_poly)); 00257 else 00258 nearby_poly = pops->getClosestPoly(plan, MapPose(estimate->pose.pose)); 00259 00260 if (aim_poly.poly_id != -1 00261 && aim_index >= 0 00262 && aim_index < (int) plan.size() - 1) 00263 { 00264 if (nearby_poly >= 0) 00265 { 00266 int aim_index2 = pops->index_of_downstream_poly 00267 (plan,nearby_poly,target_dist); 00268 00269 if (aim_index2 > aim_index && aim_index2 < (int) plan.size()-1) 00270 { 00271 aim_index = aim_index2; 00272 aim_poly.poly_id = -1; // no aim polygon defined 00273 } 00274 } 00275 00276 aim_distance = Euclidean::DistanceTo(plan.at(aim_index+1).midpoint, 00277 plan.at(aim_index).midpoint); 00278 aim_next_heading = atan2f(plan.at(aim_index+1).midpoint.y- 00279 plan.at(aim_index).midpoint.y, 00280 plan.at(aim_index+1).midpoint.x- 00281 plan.at(aim_index).midpoint.x); 00282 00283 aim_in_plan = true; 00284 00285 ROS_DEBUG("steering down the lane toward polygon %d", 00286 plan.at(aim_index).poly_id); 00287 } 00288 else 00289 { 00290 if (nearby_poly >= 0) 00291 { 00292 ROS_DEBUG("nearby_poly in desired_heading() is %d", 00293 plan.at(nearby_poly).poly_id); 00294 00295 // set aim_polar to the closest polygon at least target_dist 00296 // meters away from the estimated position. 00297 aim_index = 00298 pops->index_of_downstream_poly(plan, nearby_poly, 00299 target_dist); 00300 if (aim_index >= 0 && aim_index < (int)plan.size()-1) 00301 { 00302 // Polygon at target distance 00303 aim_distance = 00304 Euclidean::DistanceTo(plan.at(aim_index+1).midpoint, 00305 plan.at(aim_index).midpoint); 00306 00307 aim_next_heading = atan2f(plan.at(aim_index+1).midpoint.y- 00308 plan.at(aim_index).midpoint.y, 00309 plan.at(aim_index+1).midpoint.x- 00310 plan.at(aim_index).midpoint.x); 00311 00312 aim_in_plan = true; 00313 00314 ROS_DEBUG("steering at least %.3fm " 00315 "down the lane toward polygon %d", 00316 target_dist, plan.at(aim_index).poly_id); 00317 } 00318 else 00319 { 00320 // No polygon in target distance. Head to next way-point 00321 ROS_WARN_THROTTLE(40, "no polygon at least %.3fm away, " 00322 "steer using waypoints", target_dist); 00323 aim_polar = head_for_waypt(target_dist); 00324 00325 aim_distance = aim_polar.range; 00326 aim_next_heading = 00327 normalize(MapPose(estimate->pose.pose).yaw 00328 + aim_polar.heading); 00329 } 00330 } 00331 else 00332 { 00333 // no plan available: a big problem, but must do 00334 // something. Go to next waypoint. 00335 00336 ROS_WARN_THROTTLE(40, "no lane data available, " 00337 "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 ROS_DEBUG("Thresholding speed to %.3f m/s", used_velocity); 00384 00385 float spring_yaw; 00386 if (aim_in_plan) 00387 spring_yaw = get_yaw_spring_system(aim_polar, aim_index, 00388 aim_next_heading, 00389 max_yaw_rate, used_velocity, 00390 offset_ratio); 00391 else 00392 spring_yaw = get_yaw_spring_system(aim_polar, -1, aim_next_heading, 00393 max_yaw_rate, used_velocity); 00394 00395 pcmd.yawRate = spring_yaw; 00396 00397 #if 0 00398 if (Epsilon::equal(pcmd.yawRate,max_yaw_rate)) 00399 pcmd.velocity = fminf(pcmd.velocity,Steering::steer_speed_min); 00400 #endif 00401 00402 nav->trace_controller("desired_heading", pcmd); 00403 } 00404 00405 // return distance in the plan to a way-point 00406 float Course::distance_in_plan(const MapPose &from, 00407 const WayPointNode &wp) const 00408 { 00409 if (plan.empty()) 00410 return Euclidean::DistanceToWaypt(from, wp); 00411 else return pops->distanceAlongLane(plan, from.map, wp.map); 00412 } 00413 00414 // return distance in plan to a pose 00415 float Course::distance_in_plan(const MapPose &from, 00416 const MapPose &to) const 00417 { 00418 if (plan.empty()) 00419 return Euclidean::DistanceTo(from, to); 00420 else return pops->distanceAlongLane(plan, from.map, to.map); 00421 } 00422 00423 float Course::distance_in_plan(const MapPose &from, 00424 const MapXY &to) const 00425 { 00426 if (plan.empty()) 00427 return Euclidean::DistanceTo(from.map, to); 00428 else return pops->distanceAlongLane(plan, from.map,to); 00429 } 00430 00431 00432 // Course class termination for run state cycle. 00433 // 00434 // entry: 00435 // waypoint_checked true if any controller has checked that a new 00436 // way-point has been reached. 00437 // 00438 void Course::end_run_cycle() 00439 { 00440 if (!waypoint_checked) 00441 ROS_ERROR("failed to check for way-point reached!"); 00442 } 00443 00444 // find an aim polygon ahead of the car in lane 00445 // 00446 // The selected polygon is at least min_lane_change_dist away. The 00447 // exact choice depends on the distance of the car from the lane, and 00448 // its velocity. 00449 // 00450 // returns: index of aim polygon, -1 if none 00451 // 00452 int Course::find_aim_polygon(poly_list_t &lane) 00453 { 00454 00455 poly_list_t edge; 00456 pops->add_polys_for_waypts(lane,edge,order->waypt[0].id, 00457 order->waypt[1].id); 00458 00459 // get closest polygon to estimated position 00460 int nearby_poly = pops->getClosestPoly(edge, MapPose(estimate->pose.pose)); 00461 if (nearby_poly < 0) 00462 nearby_poly = pops->getClosestPoly(lane, MapPose(estimate->pose.pose)); 00463 else 00464 nearby_poly = pops->getPolyIndex(lane,edge.at(nearby_poly)); 00465 00466 if (nearby_poly < 0) 00467 return -1; 00468 00469 #if 1 00470 float aim_distance = min_lane_steer_dist; 00471 00472 ROS_DEBUG("aim point %.3fm ahead", aim_distance); 00473 00474 return pops->index_of_downstream_poly(lane, nearby_poly, aim_distance); 00475 00476 #else 00477 00478 // increase aim_distance if the lane is far away 00479 float lane_distance = 00480 pops->getShortestDistToPoly(MapPose(estimate->pose.pose), lane.at(nearby_poly)); 00481 00482 if (Epsilon::equal(lane_distance,0.0)) 00483 return -1; 00484 00485 float lane_change_distance_ratio = estimate->vel.x; 00486 float aim_distance; 00487 00488 if (req_max_dist < Infinite::distance) 00489 aim_distance = req_max_dist; 00490 else 00491 { 00492 // Try based on speed -- may be too far or 0 (if not moving) 00493 aim_distance = fminf(lane_distance * lane_change_distance_ratio, 00494 estimate->vel.x * lane_change_secs); 00495 } 00496 00497 float max_pass_distance = ArtVehicle::length*4; 00498 00499 // Threshold by maximum distance to get over. 00500 aim_distance = fminf(max_pass_distance,aim_distance); 00501 00502 if (order->waypt[1].is_goal) 00503 { 00504 float way_dist = distance_in_plan(MapPose(estimate->pose.pose), 00505 order->waypt[1]); 00506 aim_distance = fminf(aim_distance,way_dist); 00507 } 00508 00509 // At least look as far ahead as bumper 00510 aim_distance = fmaxf(aim_distance, ArtVehicle::front_bumper_px); 00511 00512 ROS_DEBUG("lane is %.3fm away, aim point %.3fm ahead", 00513 lane_distance, aim_distance); 00514 00515 return pops->index_of_downstream_poly(lane, nearby_poly, aim_distance); 00516 00517 #endif 00518 } 00519 00520 // Find an appropriate polygon path for passing an obstacle blocking 00521 // the current travel lane. 00522 // 00523 // Note that an obstacle could be on a checkpoint. DARPA said that 00524 // checkpoints would be in driveable locations. But, another car 00525 // could still stop there. Our implementation will pass it anyway and 00526 // consider the checkpoint reached when the car passes it. That does 00527 // not meet the requirement that the front bumper pass over the 00528 // checkpoint, but follows the DARPA Technical FAQ recommendation. 00529 // 00530 // exit: 00531 // sets adj_lane[passing_lane], adj_polys[passing_lane] 00532 // sets passing_left true iff passing to the left 00533 // leaves Course::plan alone 00534 // returns true, if alternate lane found 00535 // 00536 bool Course::find_passing_lane(void) 00537 { 00538 ROS_DEBUG("find passing lane around waypoint %s", 00539 ElementID(order->waypt[1].id).name().str); 00540 00541 // generate adjacent lane IDs 00542 adj_lane[0] = order->waypt[1].id; 00543 --adj_lane[0].lane; // next lower lane number 00544 00545 adj_lane[1] = order->waypt[1].id; 00546 ++adj_lane[1].lane; // next higher lane number 00547 00548 #if 1 // more general implementation, experimental 00549 00550 int cur_index = pops->getClosestPoly(plan, MapPose(estimate->pose.pose)); 00551 if (cur_index == -1) 00552 { 00553 ROS_WARN("no polygon nearby in plan"); 00554 return false; 00555 } 00556 poly cur_poly = plan.at(cur_index); 00557 00558 // collect polygons for any adjacent lanes and determine their 00559 // relative position and direction. 00560 int left_lane = -1; // no left lane 00561 int right_lane = -1; // no right lane 00562 bool adj_forw[2]; // true if going forward 00563 00564 for (unsigned i = 0; i < 2; ++i) 00565 { 00566 adj_lane[i].pt = 0; // lane ID, not way-point 00567 adj_polys[i].clear(); 00568 if (adj_lane[i].lane == 0) // ID not valid? 00569 continue; 00570 00571 // collect lane polygons 00572 pops->AddLanePolys(polygons, adj_polys[i], adj_lane[i]); 00573 int this_index = 00574 pops->getClosestPoly(adj_polys[i], 00575 MapXY(order->waypt[1].mapxy)); 00576 if (this_index < 0) // no polygon found? 00577 continue; 00578 00579 // see if it is right or left of current lane 00580 poly this_poly = adj_polys[i].at(this_index); 00581 if (pops->left_of_poly(this_poly, cur_poly)) 00582 left_lane = i; 00583 else 00584 right_lane = i; 00585 00586 // see if it goes forward or backward 00587 adj_forw[i] = pops->same_direction(cur_poly, this_poly, HALFPI); 00588 if (!adj_forw[i]) 00589 { 00590 // collect polygons in reverse direction, instead 00591 adj_polys[i].clear(); 00592 pops->AddReverseLanePolys(polygons, adj_polys[i], adj_lane[i]); 00593 } 00594 00595 if (verbose >= 4) 00596 log(adj_lane[i].lane_name().str, adj_polys[i]); 00597 } 00598 00599 // pick the preferred lane and direction 00600 if (right_lane >= 0 00601 && adj_forw[right_lane]) 00602 passing_lane = right_lane; // right lane, forward 00603 else if (left_lane >= 0 00604 && adj_forw[left_lane]) 00605 passing_lane = left_lane; // left lane, forward 00606 else if (right_lane >= 0) 00607 passing_lane = right_lane; // right lane, backward 00608 else if (left_lane >= 0) 00609 passing_lane = left_lane; // left lane, backward 00610 else 00611 { 00612 passing_lane = -1; 00613 ROS_WARN("no passing lane available for waypoint %s", 00614 ElementID(order->waypt[1].id).name().str); 00615 return false; 00616 } 00617 00618 // save direction for turn signals 00619 passing_left = (passing_lane == left_lane); 00620 00621 ROS_INFO("passing lane %s selected, to %s going %s", 00622 adj_lane[passing_lane].lane_name().str, 00623 (passing_left? "left": "right"), 00624 (adj_forw[passing_lane]? "forward": "backward")); 00625 00626 #else // old version 00627 00628 for (unsigned i = 0; i < 2; ++i) 00629 { 00630 // TODO: use pops->PolyHeading() to determine direction of 00631 // passing lane. (This code reproduces site visit capability, 00632 // so it is always reversed.) 00633 adj_lane[i].pt = 0; // lane ID, not way-point 00634 adj_polys[i].clear(); 00635 if (adj_lane[i].lane > 0) // ID in valid range? 00636 { 00637 pops->AddReverseLanePolys(polygons, adj_polys[i], adj_lane[i]); 00638 } 00639 if (verbose >= 4) 00640 log(adj_lane[i].lane_name().str, adj_polys[i]); 00641 } 00642 00643 // find a non-empty lane 00644 passing_lane = 1; 00645 while (passing_lane >= 0 && adj_polys[passing_lane].empty()) 00646 { 00647 --passing_lane; 00648 } 00649 00650 // if there are no polygons at all, or no adjacent lane in this 00651 // segment, return failure 00652 if (passing_lane < 0) 00653 { 00654 ROS_WARN("no passing lane available for waypoint %s", 00655 order->waypt[1].id.name().str); 00656 return false; 00657 } 00658 00659 passing_left = true; // always left for now 00660 00661 ROS_DEBUG("passing lane %s selected", 00662 adj_lane[passing_lane].lane_name().str); 00663 00664 #endif 00665 00666 return true; 00667 } 00668 00669 // Find a path in the travel lane to the next few way-points. 00670 // 00671 // We want the sequence of polygons that will take us from our current 00672 // position to the order->waypt[].id polygons, avoiding wrong paths 00673 // through any intersection. 00674 // 00675 // entry: rejoin is true when the car is currently outside the lane 00676 // 00677 void Course::find_travel_lane(bool rejoin) 00678 { 00679 if (plan_valid()) 00680 { 00681 ROS_DEBUG("find_travel_lane() plan still valid"); 00682 } 00683 else 00684 { 00685 // make a new plan 00686 plan.clear(); 00687 aim_poly.poly_id = -1; // no aim polygon defined 00688 set_plan_waypts(); 00689 00690 if (polygons.size() == 0) // no lane data available? 00691 { 00692 ROS_WARN("find_travel_lane() has no polygons"); 00693 return; 00694 } 00695 00696 // push waypt[0] polygon onto the plan 00697 pops->add_polys_for_waypts(polygons, plan, 00698 order->waypt[0].id, order->waypt[0].id); 00699 if (verbose >= 6) 00700 log("debug plan", plan); 00701 00702 // add polygons leading to the target waypt entries 00703 for (int i = 1; i < Order::N_WAYPTS; ++i) 00704 { 00705 // Do not repeat polygons for repeated way-points in the order. 00706 if (ElementID(order->waypt[i-1].id) 00707 != ElementID(order->waypt[i].id)) 00708 // Collect all polygons from previous waypt to this one and 00709 // also the polygon containing this one. 00710 pops->add_polys_for_waypts(polygons, plan, 00711 order->waypt[i-1].id, 00712 order->waypt[i].id); 00713 // don't plan past a zone entry 00714 if (order->waypt[i].is_perimeter) 00715 break; 00716 } 00717 00718 if (plan.size() > 1) 00719 { 00720 ROS_DEBUG("plan[0] start, end waypoints are %s, %s, poly_id = %d", 00721 plan.at(0).start_way.name().str, 00722 plan.at(0).end_way.name().str, 00723 plan.at(0).poly_id); 00724 ROS_DEBUG("plan[1] start, end waypoints are %s, %s, poly_id = %d", 00725 plan.at(1).start_way.name().str, 00726 plan.at(1).end_way.name().str, 00727 plan.at(1).poly_id); 00728 } 00729 log("find_travel_lane() plan", plan); 00730 } 00731 00732 new_plan_lanes = false; // plan reflects current lanes 00733 aim_poly.poly_id = -1; // no aim polygon defined 00734 00735 if (rejoin) 00736 { 00737 // If the car is outside its lane, select appropriate polygon to 00738 // rejoin it. Otherwise, the car may overshoot and circle back, 00739 // which would be very bad. This also prevents the follow 00740 // safely controller from getting confused after passing an 00741 // obstacle in the target lane. 00742 00743 // Beware: when approaching the site visit intersection the loop 00744 // in segment one causes find_aim_polygon(lane_polys) to pick 00745 // the wrong end of the lane, causing the car to turn the wrong 00746 // way. So, first look it up in plan, then find the 00747 // corresponding index in lane_polys. 00748 00749 // find a polygon slightly ahead of the car 00750 int aim_index = find_aim_polygon(plan); 00751 if (aim_index >= 0) 00752 { 00753 // set aim polygon for obstacle avoidance 00754 aim_poly = plan.at(aim_index); 00755 ROS_DEBUG("aim polygon is %d", aim_poly.poly_id); 00756 } 00757 } 00758 } 00759 00760 // Head directly for next reachable way-point. 00761 // 00762 // This is trouble: the plan stops too soon for navigating 00763 // by polygons. Have to do something, so head directly for 00764 // the next way-point, but make sure it's far enough away 00765 // that the car does not double back to it. 00766 Polar Course::head_for_waypt(float target_dist) 00767 { 00768 using Coordinates::MapXY_to_Polar; 00769 Polar aim_polar = MapXY_to_Polar(MapXY(order->waypt[1].mapxy), 00770 *estimate); 00771 if (aim_polar.range < target_dist) 00772 { 00773 if (special_waypt(1)) 00774 { 00775 // If the next way-point is a stop or U-turn, go straight 00776 // and try to reach it. 00777 ART_MSG(8, "waypt[1] is a special way-point, keep current heading"); 00778 aim_polar.heading=0.0; 00779 } 00780 else if (order->waypt[1].is_perimeter) 00781 { 00782 ART_MSG(8, "waypt[1] is a perimeter point"); 00783 aim_polar = MapXY_to_Polar(MapXY(order->waypt[1].mapxy), 00784 *estimate); 00785 if (fabsf(bearing(MapPose(estimate->pose.pose), 00786 MapXY(order->waypt[1].mapxy))) 00787 > HALFPI) 00788 new_waypoint_reached(order->waypt[1].id); 00789 } 00790 else 00791 { 00792 // waypt[1] is too close, steer for waypt[2] instead 00793 aim_polar = MapXY_to_Polar(MapXY(order->waypt[2].mapxy), 00794 *estimate); 00795 ART_MSG(8, "waypt[1] less than %.3fm away, using waypt[2] instead", 00796 target_dist); 00797 // claim we got there (we're at least close) 00798 new_waypoint_reached(order->waypt[1].id); 00799 } 00800 } 00801 return aim_polar; 00802 } 00803 00804 // return lane change direction 00805 Course::direction_t Course::lane_change_direction(void) 00806 { 00807 int w0_index = pops->get_waypoint_index(polygons, order->waypt[0].id); 00808 int w1_index = pops->get_waypoint_index(polygons, order->waypt[1].id); 00809 00810 // give up unless both polygons are available 00811 if (w0_index < 0 || w1_index < 0) 00812 return Straight; 00813 00814 if (pops->left_of_poly(polygons.at(w1_index), polygons.at(w0_index))) 00815 return Left; 00816 else 00817 return Right; 00818 } 00819 00820 // check if lane way-point reached 00821 // 00822 // Considers a way-point reached when the car is in front of the pose 00823 // formed by the way-point and the heading of its containing polygon. 00824 // 00825 // exit: navdata->last_waypt updated 00826 // returns: true if order->waypt[1] reached (unless a special way-point) 00827 // 00828 // bugs: Does not work for zone perimeter way-points because they do 00829 // not have a containing polygon. Those are detected by the 00830 // stop_line controller, instead. 00831 // 00832 bool Course::lane_waypoint_reached(void) 00833 { 00834 // Mark the way-point checked, even if it is a special one. 00835 waypoint_checked = true; 00836 00837 if (order->waypt[1].is_perimeter) 00838 return zone_perimeter_reached(); 00839 00840 // Special way-points (stop, U-turn) are handled explicitly 00841 // elsewhere by their state-specific controllers. They cause state 00842 // transitions, so they must be ignored here and only considered 00843 // "reached" when the requirements of those specific controllers are 00844 // fully met. 00845 if (special_waypt(1)) 00846 return false; 00847 00848 #ifdef USE_PATS 00849 ElementID last_way = pops->updateLaneLocation(polygons, 00850 odom->pose, 00851 order->waypt[0], 00852 order->waypt[1]); 00853 if (last_way == order->waypt[1].id) 00854 { 00855 navdata->last_way = last_way; 00856 return true; 00857 } 00858 return false; 00859 #endif 00860 00861 bool found = false; 00862 00863 // Instead of checking a circle about the way-point, see if the 00864 // car has reached a line through the way-point perpendicular to 00865 // the direction of its lane. 00866 00867 // get polygon index of waypt[1] (TODO: save somewhere) 00868 int w1_index = -1; 00869 00870 w1_index = pops->get_waypoint_index(polygons, order->waypt[1].id); 00871 00872 if (w1_index >= 0) 00873 { 00874 // form way-point pose using polygon heading 00875 // TODO: save somewhere 00876 MapPose w1_pose(MapXY(order->waypt[1].mapxy), 00877 pops->PolyHeading(polygons.at(w1_index))); 00878 00879 // Is the bearing of the car from that pose within 90 00880 // degrees of the polygon heading? 00881 float bearing_from_w1 = bearing(w1_pose, 00882 MapXY(odom->pose.pose.position)); 00883 if (fabsf(bearing_from_w1) < angles::from_degrees(90)) 00884 { 00885 // The car is "in front" of this way-point's pose. 00886 ROS_INFO("reached waypoint %s, bearing %.3f radians", 00887 ElementID(order->waypt[1].id).name().str, 00888 bearing_from_w1); 00889 navdata->last_waypt = order->waypt[1].id; 00890 found = true; 00891 } 00892 } 00893 00894 00895 if (!found) 00896 ROS_DEBUG("cur_poly = %d, last_waypt = %s", 00897 navdata->cur_poly, 00898 ElementID(navdata->last_waypt).name().str); 00899 return found; 00900 } 00901 00907 void Course::lanes_message(const art_msgs::ArtLanes &lanes) 00908 { 00909 // copy polygons from message 00910 polygons.resize(lanes.polygons.size()); 00911 for (unsigned num = 0; num < lanes.polygons.size(); num++) 00912 polygons.at(num) = lanes.polygons[num]; 00913 00914 if (polygons.empty()) 00915 ROS_WARN("empty lanes polygon list received!"); 00916 00917 // force plan to be recomputed 00918 new_plan_lanes = true; 00919 00920 log("lanes input:", polygons); 00921 }; 00922 00923 // log a vector of polygons 00924 void Course::log(const char *str, const poly_list_t &polys) 00925 { 00926 unsigned npolys = polys.size(); 00927 if (npolys > 0) 00928 { 00929 for (unsigned i = 0; i < npolys; ++i) 00930 { 00931 ROS_DEBUG("polygon[%u] = %d", i, polys.at(i).poly_id); 00932 unsigned start_seq = i; 00933 while (i+1 < npolys 00934 && abs(polys.at(i+1).poly_id - polys.at(i).poly_id) == 1) 00935 { 00936 ++i; 00937 } 00938 if (start_seq == i) 00939 ROS_DEBUG("%s polygon at %d", str, polys.at(i).poly_id); 00940 else 00941 ROS_DEBUG("%s polygons from %d to %d", 00942 str, polys.at(start_seq).poly_id, polys.at(i).poly_id); 00943 } 00944 } 00945 else 00946 { 00947 ROS_INFO("%s no polygons at all", str); 00948 } 00949 } 00950 00951 // return true if current order does not match saved way-points 00952 bool Course::new_waypts(void) 00953 { 00954 if (saved_replan_num!=order->replan_num) 00955 return true; 00956 00957 for (unsigned i = 0; i < art_msgs::Order::N_WAYPTS; ++i) 00958 if (saved_waypt_id[i] != order->waypt[i].id) 00959 return true; 00960 00961 // still the same 00962 return false; 00963 } 00964 00965 // reset course class 00966 void Course::reset(void) 00967 { 00968 ROS_INFO("Course class reset()"); 00969 00970 // TODO: figure out when this needs to happen and what to do 00971 start_pass_location = MapPose(); 00972 00973 // clear the previous plan 00974 plan.clear(); 00975 aim_poly.poly_id = -1; 00976 } 00977 00978 // replan after road block 00979 ElementID Course::replan_roadblock(void) 00980 { 00981 saved_replan_num=order->replan_num; 00982 00983 // save current order way-points 00984 for (unsigned i = 0; i < art_msgs::Order::N_WAYPTS; ++i) 00985 { 00986 saved_waypt_id[i] = order->waypt[i].id; 00987 ROS_DEBUG("saved_waypt_id[%u] = %s", 00988 i, saved_waypt_id[i].name().str); 00989 } 00990 00991 // Get closest polygon in current plan. 00992 int uturn_exit_index = 00993 pops->getClosestPoly(plan,MapPose(estimate->pose.pose)); 00994 00995 MapPose exit_pose; 00996 exit_pose.map.x=plan.at(uturn_exit_index).midpoint.x; 00997 exit_pose.map.y=plan.at(uturn_exit_index).midpoint.y; 00998 00999 // Should get lane left of current position. If in transition, the 01000 // lane should be left of previous lane left. 01001 ElementID reverse_lane = 01002 pops->getReverseLane(polygons,exit_pose); 01003 01004 ROS_INFO("Replan from lane %s", reverse_lane.lane_name().str); 01005 01006 return reverse_lane; 01007 } 01008 01009 // direction for crossing an intersection 01010 Course::direction_t Course::intersection_direction(void) 01011 { 01012 int w0_index = 01013 pops->getContainingPoly(polygons, 01014 MapXY(order->waypt[0].mapxy)); 01015 int w1_index = 01016 pops->getContainingPoly(polygons, 01017 MapXY(order->waypt[1].mapxy)); 01018 01019 // give up unless both polygons are available 01020 if (w0_index < 0 || w1_index < 0) 01021 return Straight; 01022 01023 float w0_heading = pops->PolyHeading(polygons.at(w0_index)); 01024 float w1_heading = pops->PolyHeading(polygons.at(w1_index)); 01025 float heading_change = normalize(w1_heading - w0_heading); 01026 01027 ROS_DEBUG("heading change from waypoint %s to %s is %.3f radians", 01028 ElementID(order->waypt[0].id).name().str, 01029 ElementID(order->waypt[1].id).name().str, 01030 heading_change); 01031 01032 if (fabsf(heading_change) < angles::from_degrees(30)) 01033 return Straight; 01034 else if (heading_change > 0.0) 01035 return Left; 01036 else 01037 return Right; 01038 } 01039 01040 // true if order has an upcoming stop way-point 01041 // 01042 // exit: sets stop_waypt, stop_poly if found 01043 // 01044 float Course::stop_waypt_distance(bool same_lane) 01045 { 01046 for (unsigned i = 1; i < art_msgs::Order::N_WAYPTS; ++i) 01047 { 01048 // only consider way-points in the current lane 01049 if (same_lane 01050 && !ElementID(order->waypt[i].id).same_lane(order->waypt[0].id)) 01051 break; 01052 01053 if (order->waypt[i].is_stop) 01054 { 01055 // find stop way-point polygon 01056 int stop_index = 01057 pops->getContainingPoly(polygons, 01058 MapXY(order->waypt[i].mapxy)); 01059 if (stop_index < 0) // none found? 01060 continue; // keep looking 01061 01062 stop_poly = polygons.at(stop_index); 01063 stop_waypt = WayPointNode(order->waypt[i]); 01064 float wayptdist = distance_in_plan(MapPose(estimate->pose.pose), 01065 stop_waypt); 01066 ROS_DEBUG("Stop at waypoint %s is %.3fm away", 01067 stop_waypt.id.name().str, wayptdist); 01068 return wayptdist; 01069 } 01070 } 01071 return Infinite::distance; 01072 } 01073 01074 // switch to previously selected passing lane 01075 // 01076 // entry: 01077 // adj_lane[passing_lane].id is the passing lane ID 01078 // adj_polys[passing_lane] contains its polygons 01079 // obstacle is polar coordinate of nearest obstacle in plan 01080 // exit: 01081 // plan contains polygons to follow 01082 // passed_lane contains previous plan polygons 01083 // start_pass_location set to current pose, with polygon heading 01084 // returns true if successful 01085 // 01086 bool Course::switch_to_passing_lane() 01087 { 01088 // find a polygon slightly ahead of the car 01089 int aim_index = find_aim_polygon(adj_polys[passing_lane]); 01090 if (aim_index == -1) 01091 { 01092 ROS_WARN("unable to pass, no polygon near the aiming point"); 01093 return false; 01094 } 01095 01096 // save original plan for checking when it is safe to return 01097 passed_lane = plan; 01098 01099 // collect all the polygons from aim_index to end of passing lane 01100 plan.clear(); 01101 pops->CollectPolys(adj_polys[passing_lane], plan, aim_index); 01102 01103 log("switch_to_passing_lane() plan", plan); 01104 if (plan.empty()) 01105 { 01106 ROS_WARN("no polygons in passing lane past aiming point"); 01107 return false; 01108 } 01109 01110 aim_poly=plan.at(0); 01111 MapXY aim_poly_midpt = pops->getPolyEdgeMidpoint(aim_poly); 01112 ROS_DEBUG("aiming at polygon %d, midpoint (%.3f, %.3f)", 01113 aim_poly.poly_id, aim_poly_midpt.x, aim_poly_midpt.y); 01114 01115 MapXY start_point = 01116 pops->GetClosestPointToLine (pops->midpoint(aim_poly.p1,aim_poly.p4), 01117 pops->midpoint(aim_poly.p2,aim_poly.p3), 01118 MapXY(estimate->pose.pose.position), 01119 true); 01120 01121 start_pass_location.map=start_point; 01122 start_pass_location.yaw=aim_poly.heading; 01123 01124 ROS_INFO("passing starts at (%.3f, %.3f)", 01125 start_pass_location.map.x, start_pass_location.map.y); 01126 01127 return true; 01128 } 01129 01130 // return distance to upcoming U-turn way-point, Infinite::distance if none. 01131 float Course::uturn_distance(void) 01132 { 01133 int i = uturn_order_index(); 01134 if (i < 0) 01135 return Infinite::distance; 01136 01137 // find stop way-point polygon 01138 int stop_index = 01139 pops->getContainingPoly(polygons, 01140 MapXY(order->waypt[i].mapxy)); 01141 if (stop_index < 0) // none found? 01142 return Infinite::distance; 01143 01144 // save way-point and polygon for stop_line controller 01145 stop_poly = polygons.at(stop_index); 01146 stop_waypt = WayPointNode(order->waypt[i]); 01147 01148 // compute distance remaining 01149 float wayptdist = distance_in_plan(MapPose(estimate->pose.pose), stop_waypt); 01150 ROS_DEBUG("U-turn at waypoint %s, %.3fm away", 01151 stop_waypt.id.name().str, wayptdist); 01152 return wayptdist; 01153 } 01154 01155 // return index of upcoming U-turn transition in order->waypt array 01156 // 01157 // A U-turn is represented in the RNDF by an exit way-point in one 01158 // lane pointing to a matching entry way-point in an adjacent lane. 01159 // 01160 int Course::uturn_order_index(void) 01161 { 01162 for (unsigned i = 1; i < art_msgs::Order::N_WAYPTS-1; ++i) 01163 { 01164 // only consider way-points in the current lane 01165 if (!ElementID(order->waypt[i].id).same_lane(ElementID(order->waypt[0].id))) 01166 break; 01167 01168 if (uturn_waypt(i)) 01169 return i; 01170 } 01171 return -1; 01172 } 01173 01174 // return true if waypt[windex] and waypt[windex+1] are a U-turn pair 01175 bool Course::uturn_waypt(unsigned windex) 01176 { 01177 if (order->next_uturn < 0) 01178 return false; 01179 01180 return (windex==(unsigned)order->next_uturn); 01181 } 01182 01183 // check if zone way-point reached 01184 // 01185 // Considers a way-point reached when the front of the car is within 01186 // zone_waypoint_radius of the way-point. 01187 // 01188 // exit: navdata->last_waypt updated 01189 // returns: true if order->waypt[1] reached 01190 // 01191 bool Course::zone_waypoint_reached(void) 01192 { 01193 bool found = false; 01194 waypoint_checked = true; 01195 01196 // polar coordinate of front bumper from estimated position 01197 Polar bumper_polar(0.0, ArtVehicle::front_bumper_px); 01198 float distance = 01199 Euclidean::DistanceToWaypt(bumper_polar, 01200 MapPose(estimate->pose.pose), 01201 WayPointNode(order->waypt[1])); 01202 01203 if (distance <= zone_waypoint_radius) 01204 { 01205 // The car is near this way-point. 01206 ROS_DEBUG("reached zone waypoint %s, distance %.3fm", 01207 ElementID(order->waypt[1].id).name().str, distance); 01208 navdata->last_waypt = order->waypt[1].id; 01209 found = true; 01210 } 01211 else 01212 { 01213 ROS_DEBUG("distance to zone waypoint %s is %.3fm", 01214 ElementID(order->waypt[1].id).name().str, distance); 01215 } 01216 01217 return found; 01218 } 01219 01220 bool Course::zone_perimeter_reached(void) 01221 { 01222 bool found = false; 01223 waypoint_checked = true; 01224 01225 int w1_index = 01226 pops->getClosestPoly(polygons, 01227 MapXY(order->waypt[1].mapxy)); 01228 if (w1_index >= 0) 01229 { 01230 // form way-point pose using polygon heading 01231 // TODO: save somewhere 01232 MapPose w1_pose(order->waypt[1].mapxy, 01233 pops->PolyHeading(polygons.at(w1_index))); 01234 01235 #if 1 01236 // Is the bearing of the car from that pose within 90 01237 // degrees of the polygon heading? 01238 float bearing_from_w1 = 01239 bearing(w1_pose, MapXY(odom->pose.pose.position)); 01240 #else // experimental code -- not working right yet 01241 // Is the bearing of a point slightly ahead of the front bumper 01242 // from that pose within 90 degrees of the polygon heading? 01243 Polar bumper_polar(0.0, 01244 (ArtVehicle::front_bumper_px 01245 + DARPA_rules::stop_line_to_bumper)); 01246 MapXY bumper_pos = Polar_to_MapXY(bumper_polar, odom->pos); 01247 float bearing_from_w1 = bearing(w1_pose, bumper_pos); 01248 #endif 01249 if (fabsf(bearing_from_w1) < angles::from_degrees(90)) 01250 { 01251 // The car is "in front" of this way-point's pose. 01252 ROS_DEBUG("reached waypoint %s, bearing %.3f radians", 01253 ElementID(order->waypt[1].id).name().str, 01254 bearing_from_w1); 01255 navdata->last_waypt = order->waypt[1].id; 01256 found = true; 01257 } 01258 } 01259 01260 return found; 01261 } 01262 01263 01264 bool Course::spot_waypoint_reached(void) 01265 { 01266 bool found = false; 01267 waypoint_checked = true; 01268 01269 // polar coordinate of front bumper from estimated position 01270 Polar bumper_polar(0.0, ArtVehicle::front_bumper_px); 01271 float distance = 01272 Euclidean::DistanceToWaypt(bumper_polar, MapPose(estimate->pose.pose), 01273 WayPointNode(order->waypt[1])); 01274 01275 if (distance <= spot_waypoint_radius) 01276 { 01277 // The car is near this way-point. 01278 ROS_DEBUG("reached spot waypoint %s, distance %.3fm", 01279 ElementID(order->waypt[1].id).name().str, distance); 01280 navdata->last_waypt = order->waypt[1].id; 01281 found = true; 01282 } 01283 else 01284 { 01285 ROS_DEBUG("distance to spot waypoint %s is %.3fm", 01286 ElementID(order->waypt[1].id).name().str, distance); 01287 } 01288 01289 return found; 01290 } 01291 01292 float Course::max_speed_for_slow_down(const float& final_speed, 01293 const float& distance, 01294 const float& max, 01295 const float& max_deceleration) { 01296 // This function answers the question: 01297 // 01298 // What is the fastest I could be going right now such that I can be 01299 // travelling at <final_speed> in <distance> without exceeding 01300 // <max_deceleration> between now and then? 01301 // 01302 // It uses one of the basic kinematic equations: 01303 // Vf^2 = Vi^2 + 2 * a * (Xf - Xi) 01304 01305 01306 float vf2 = final_speed * final_speed; 01307 float tax = 2 * (-max_deceleration) * distance; 01308 01309 // Return 0 if it's impossible to stop in time! 01310 if(tax > vf2) 01311 return 0.0; 01312 01313 return fminf(max, sqrtf(vf2 - tax)); 01314 } 01315 01316 // This function answers the question: 01317 // 01318 // What is the fastest I could be going right now such that my 01319 // heading changes <dheading> over the next <distance>, but I never 01320 // exceed <maximum_yaw_rate>? 01321 float Course::max_speed_for_change_in_heading(const float& dheading, 01322 const float& distance, 01323 const float& max, 01324 const float& maximum_yaw_rate) 01325 { 01326 if (Epsilon::equal(dheading,0)) 01327 { 01328 return max; 01329 } 01330 else 01331 { 01332 float new_speed=fminf(max, 01333 fmaxf(max_speed_for_sharp, 01334 fabsf(heading_change_ratio * 01335 (maximum_yaw_rate / dheading)))); 01336 ROS_DEBUG("slow for heading: distance: %.3f, dheading: %.3f, " 01337 "maximum_yaw_rate: %.3f, max_speed: %.3f, final: %.3f", 01338 distance, dheading, maximum_yaw_rate, max,new_speed); 01339 return new_speed; 01340 } 01341 } 01342 01343 01344 float Course::get_yaw_spring_system(const Polar& aim_polar, 01345 int poly_id, 01346 float poly_heading, 01347 float max_yaw, 01348 float curr_velocity, 01349 float offset_ratio) 01350 { 01351 float error = 0; 01352 float theta=-aim_polar.heading; 01353 float velocity = fmaxf(curr_velocity, Steering::steer_speed_min); 01354 nav_msgs::Odometry front_est; 01355 Estimate::front_axle_pose(*estimate, front_est); 01356 ros::Duration frequency(1.0 / art_msgs::ArtHertz::NAVIGATOR); 01357 ros::Time time_in_future = (ros::Time::now() 01358 + frequency 01359 + ros::Duration(velocity * spring_lookahead)); 01360 nav_msgs::Odometry pos_est; 01361 Estimate::control_pose(front_est, time_in_future, pos_est); 01362 01363 if (poly_id >=0) 01364 { 01365 poly current_poly=plan.at(poly_id); 01366 posetype origin; // (0, 0, 0) 01367 posetype cpoly(current_poly.midpoint.x, current_poly.midpoint.y, 01368 poly_heading); 01369 rotate_translate_transform trans; 01370 trans.find_transform(cpoly,origin); 01371 posetype car(pos_est.pose.pose.position.x, 01372 pos_est.pose.pose.position.y, 01373 0.0); 01374 posetype car_rel=trans.apply_transform(car); 01375 01376 float width=Euclidean::DistanceTo(current_poly.p2,current_poly.p3); 01377 01378 // transverse offset error, positive if left of center (push right) 01379 error=car_rel.y; 01380 // ART_MSG(1,"STEER error = %lf\n", error); 01381 01382 #if 1 // still experimental: 01383 01384 if (!Epsilon::equal(offset_ratio, 0.0)) 01385 { 01386 // To steer for an offset from lane center, adjust error by 01387 // subtracting offset from polygon midpoint to middle of 01388 // left lane boundary minus width of car. 01389 01390 MapXY mid_left_side = 01391 pops->midpoint(current_poly.p1, current_poly.p2); 01392 float half_lane_width = 01393 Euclidean::DistanceTo(current_poly.midpoint, mid_left_side); 01394 float lane_space = half_lane_width - ArtVehicle::halfwidth; 01395 float error_offset = 0.0; 01396 if (lane_space > 0.0) // any room in this lane? 01397 error_offset = offset_ratio * lane_space; 01398 ROS_DEBUG("error offset %.3f, half lane width %.3f, ratio %.3f", 01399 error_offset, half_lane_width, offset_ratio); 01400 01401 // Increasing error term pushes right, decreasing left. 01402 error -= error_offset; 01403 } 01404 #endif 01405 error=fminf(fmaxf(-width,error),width); 01406 // heading error 01407 theta = normalize(MapPose(pos_est.pose.pose).yaw - poly_heading); 01408 } 01409 01410 01411 float cth = cosf(theta); 01412 01413 float vcth = velocity*cth; 01414 01415 if (fabsf(theta) >= HALFPI || 01416 Epsilon::equal(cth,0.0) || 01417 Epsilon::equal(vcth,0.0)) 01418 { 01419 ART_MSG(8,"Spring system does not apply: heading offset %.3f", theta); 01420 if (Epsilon::equal(error,0)) { 01421 if (theta < 0) 01422 return max_yaw; 01423 else return -max_yaw; 01424 } 01425 else { 01426 if (error > 0) 01427 return max_yaw; 01428 else return -max_yaw; 01429 } 01430 } 01431 01432 float d2=-k_theta*sinf(theta)/cth; 01433 float d1=-k_error*error/vcth; 01434 01435 // #ifdef NQE 01436 // if (order->waypt[0].id==ElementID(2,1,3) && 01437 // order->waypt[1].id==ElementID(1,1,2)) 01438 // { 01439 // d2=-0.7*sinf(theta)/cth; 01440 // ART_MSG(1,"Taking special turn"); 01441 // } 01442 // #endif 01443 01444 if ((Coordinates::sign(error) == Coordinates::sign(last_error)) && 01445 (fabsf(error) > fabs(last_error))) 01446 d1*=k_int; 01447 01448 last_error=error; 01449 float yaw=d1+d2; 01450 01451 ROS_DEBUG("Heading spring systems values: error %.3f, dtheta %.3f, " 01452 "d1 %.3f, d2 %.3f, d1+d2 %.3f", error, theta, d1, d2, yaw); 01453 01454 if (yaw < 0) 01455 return fmaxf(-max_yaw, yaw); 01456 return fminf(max_yaw, yaw); 01457 } 01458 01459 01460 bool Course::spot_ahead() 01461 { 01462 for (uint i=0; i<art_msgs::Order::N_WAYPTS-1;i++) 01463 if (order->waypt[i].is_spot && 01464 order->waypt[i+1].is_spot && 01465 order->waypt[i].id.pt==1 && 01466 order->waypt[i+1].id.pt==2) 01467 return true; 01468 01469 return false; 01470 01471 } 01472 01473 bool Course::curr_spot() 01474 { 01475 return order->waypt[0].is_spot; 01476 } 01477 01478 #if 0 01479 mapxy_list_t Course::calculate_zone_barrier_points() 01480 { 01481 mapxy_list_t spot_points; 01482 01483 return spot_points; 01484 01485 if (order->waypt[1].is_spot) 01486 return spot_points; 01487 01488 posetype way_pose(order->waypt[1].mapxy.x, 01489 order->waypt[1].mapxy.y, 01490 atan2f(order->waypt[2].mapxy.y-order->waypt[1].mapxy.y, 01491 order->waypt[2].mapxy.x-order->waypt[1].mapxy.x)); 01492 01493 rotate_translate_transform trans; 01494 trans.find_transform(posetype(),way_pose); 01495 01496 posetype npose; 01497 npose=trans.apply_transform(posetype(1,order->waypt[1].lane_width,0)); 01498 spot_points.push_back(npose); 01499 01500 npose=trans.apply_transform(posetype(1,order->waypt[1].lane_width/2,0)); 01501 spot_points.push_back(npose); 01502 01503 npose=trans.apply_transform(posetype(1,0,0)); 01504 spot_points.push_back(npose); 01505 01506 npose=trans.apply_transform(posetype(1,-order->waypt[1].lane_width/2,0)); 01507 spot_points.push_back(npose); 01508 01509 npose=trans.apply_transform(posetype(1,-order->waypt[1].lane_width,0)); 01510 spot_points.push_back(npose); 01511 01512 return spot_points; 01513 } 01514 01515 mapxy_list_t Course::calculate_spot_points(const std::vector<WayPointNode>& new_waypts) 01516 { 01517 mapxy_list_t spot_points; 01518 01519 for (uint i=0; i<art_msgs::Order::N_WAYPTS-1;i++) 01520 if (new_waypts[i].is_spot && 01521 new_waypts[i+1].is_spot && 01522 new_waypts[i].id.pt==1 && 01523 new_waypts[i+1].id.pt==2) 01524 { 01525 posetype way_pose(new_waypts[i].map.x,new_waypts[i].map.y, 01526 atan2f(new_waypts[i+1].map.y-new_waypts[i].map.y, 01527 new_waypts[i+1].map.x-new_waypts[i].map.x)); 01528 01529 float dist=Euclidean::DistanceTo(new_waypts[i+1].map, 01530 new_waypts[i].map); 01531 rotate_translate_transform trans; 01532 trans.find_transform(posetype(),way_pose); 01533 01534 posetype npose; 01535 01536 npose=trans.apply_transform(posetype(0,new_waypts[i].lane_width/2,0)); 01537 spot_points.push_back(npose); 01538 01539 npose=trans.apply_transform(posetype(dist,new_waypts[i].lane_width/2,0)); 01540 spot_points.push_back(npose); 01541 01542 npose=trans.apply_transform(posetype(dist+2,new_waypts[i].lane_width,0)); 01543 spot_points.push_back(npose); 01544 01545 npose=trans.apply_transform(posetype(dist+2,new_waypts[i].lane_width/2,0)); 01546 spot_points.push_back(npose); 01547 01548 npose=trans.apply_transform(posetype(dist+2,0,0)); 01549 spot_points.push_back(npose); 01550 01551 npose=trans.apply_transform(posetype(dist+2,-new_waypts[i].lane_width/2,0)); 01552 spot_points.push_back(npose); 01553 01554 npose=trans.apply_transform(posetype(dist+2,new_waypts[i].lane_width/2,0)); 01555 spot_points.push_back(npose); 01556 01557 npose=trans.apply_transform(posetype(dist,-new_waypts[i].lane_width/2,0)); 01558 spot_points.push_back(npose); 01559 01560 npose=trans.apply_transform(posetype(0,-new_waypts[i].lane_width/2,0)); 01561 spot_points.push_back(npose); 01562 01563 } 01564 return spot_points; 01565 } 01566 01567 mapxy_list_t Course::calculate_spot_points() 01568 { 01569 mapxy_list_t spot_points; 01570 01571 for (uint i=0; i<art_msgs::Order::N_WAYPTS-1;i++) 01572 if (order->waypt[i].is_spot && 01573 order->waypt[i+1].is_spot && 01574 order->waypt[i].id.pt==1 && 01575 order->waypt[i+1].id.pt==2) 01576 { 01577 posetype way_pose(order->waypt[i].mapxy.x, 01578 order->waypt[i].mapxy.y, 01579 atan2f(order->waypt[i+1].mapxy.y-order->waypt[i].mapxy.y, 01580 order->waypt[i+1].mapxy.x-order->waypt[i].mapxy.x)); 01581 01582 float dist=Euclidean::DistanceTo(order->waypt[i+1].mapxy, 01583 order->waypt[i].mapxy); 01584 rotate_translate_transform trans; 01585 trans.find_transform(posetype(),way_pose); 01586 01587 posetype npose; 01588 01589 npose=trans.apply_transform(posetype(0,order->waypt[i].lane_width/2,0)); 01590 spot_points.push_back(npose); 01591 01592 npose=trans.apply_transform(posetype(dist,order->waypt[i].lane_width/2,0)); 01593 spot_points.push_back(npose); 01594 01595 npose=trans.apply_transform(posetype(dist+2,order->waypt[i].lane_width,0)); 01596 spot_points.push_back(npose); 01597 01598 npose=trans.apply_transform(posetype(dist+2,order->waypt[i].lane_width/2,0)); 01599 spot_points.push_back(npose); 01600 01601 npose=trans.apply_transform(posetype(dist+2,0,0)); 01602 spot_points.push_back(npose); 01603 01604 npose=trans.apply_transform(posetype(dist+2,-order->waypt[i].lane_width/2,0)); 01605 spot_points.push_back(npose); 01606 01607 npose=trans.apply_transform(posetype(dist+2,order->waypt[i].lane_width/2,0)); 01608 spot_points.push_back(npose); 01609 01610 npose=trans.apply_transform(posetype(dist,-order->waypt[i].lane_width/2,0)); 01611 spot_points.push_back(npose); 01612 01613 npose=trans.apply_transform(posetype(0,-order->waypt[i].lane_width/2,0)); 01614 spot_points.push_back(npose); 01615 01616 } 01617 return spot_points; 01618 } 01619 #endif 01620 01621 bool Course::nqe_special(int i, int j) 01622 { 01623 #ifdef NQE 01624 01625 typedef struct { 01626 ElementID start; 01627 ElementID end; 01628 } id_pair; 01629 01630 static int num_pair=8; 01631 01632 static id_pair id_table[]= 01633 { 01634 //AREA A 01635 {ElementID(1,1,6),ElementID(41,1,1)}, 01636 {ElementID(1,2,5),ElementID(41,2,1)}, 01637 {ElementID(41,1,7),ElementID(1,1,1)}, 01638 {ElementID(41,2,7),ElementID(1,2,1)}, 01639 //AREA B 01640 {ElementID(6,1,10),ElementID(5,1,1)}, 01641 {ElementID(5,1,7),ElementID(6,1,1)}, 01642 {ElementID(6,1,4),ElementID(8,2,1)}, 01643 {ElementID(6,1,6),ElementID(7,1,1)}, 01644 }; 01645 01646 for (int k=0; k< num_pair; k++) 01647 if (order->waypt[i].id==id_table[k].start && 01648 order->waypt[j].id==id_table[k].end) 01649 return true; 01650 #endif 01651 01652 return false; 01653 01654 }