Navigator course planning class. More...
#include <course.h>
| Public Types | |
| enum | direction_t { Right = -1, Straight = 0, Left = 1 } | 
| Public Member Functions | |
| void | begin_run_cycle (void) | 
| Course class initialization for run state cycle. | |
| mapxy_list_t | calculate_spot_points (const std::vector< WayPointNode > &new_waypts) | 
| mapxy_list_t | calculate_spot_points () | 
| mapxy_list_t | calculate_zone_barrier_points () | 
| void | configure () | 
| set configuration variables. | |
| Course (Navigator *_nav, int _verbose) | |
| Constructor. | |
| bool | curr_spot () | 
| void | desired_heading (pilot_command_t &pcmd, float offset_ratio=0.0) | 
| set heading for desired course | |
| float | distance_in_plan (const MapPose &from, const WayPointNode &wp) const | 
| float | distance_in_plan (const MapPose &from, const MapPose &to) const | 
| float | distance_in_plan (const MapPose &from, const MapXY &to) const | 
| void | end_run_cycle (void) | 
| Course class termination for run state cycle. | |
| int | find_aim_polygon (poly_list_t &lane) | 
| bool | find_passing_lane (void) | 
| Find a passing lane through the polygons. | |
| void | find_travel_lane (bool rejoin) | 
| Find a path in the travel lane to the next few way-points. | |
| float | get_yaw_spring_system (const Polar &aim_polar, int poly_id, float poly_heading, float max_yaw, float curr_velocity, float offset_ratio=0.0) | 
| bool | in_lane (const MapPose &pose) const | 
| return true if pose is in the current travel lane | |
| bool | in_poly_list (const poly_list_t &polys, const MapPose &pose) const | 
| return true if pose is in the polys list | |
| direction_t | intersection_direction (void) | 
| return intersection crossing direction | |
| direction_t | lane_change_direction (void) | 
| return lane change direction | |
| bool | lane_waypoint_reached (void) | 
| return true if lane way-point reached | |
| void | lanes_message (const art_msgs::ArtLanes &lanes) | 
| handle lanes message | |
| void | log (const char *str, const poly_list_t &polys) | 
| log a vector of polygons | |
| float | max_speed_for_change_in_heading (const float &dheading, const float &distance, const float &max, const float &max_yaw_rate) | 
| float | max_speed_for_slow_down (const float &final_speed, const float &distance, const float &max, const float &max_deceleration) | 
| void | new_waypoint_reached (ElementID new_way) | 
| confirm that the next way-point was reached | |
| bool | new_waypts (void) | 
| return true if current order does not match saved way-points | |
| void | no_waypoint_reached (void) | 
| confirm that no way-point was reached | |
| bool | nqe_special (int i, int j) | 
| bool | plan_valid (void) | 
| return whether the current plan is still valid | |
| ElementID | replan_roadblock (void) | 
| replan after road block | |
| void | reset (void) | 
| reset course | |
| bool | same_lane (ElementID id1, ElementID id2) | 
| are id1 and id2 in the same lane? | |
| void | signal_for_direction (direction_t direction) | 
| set turn signal based on direction | |
| void | signal_pass (void) | 
| set turn signal for passing | |
| void | signal_pass_return (void) | 
| set turn signal for return from passing | |
| bool | special_waypt (unsigned windex) | 
| special way-point predicate | |
| bool | spot_ahead () | 
| bool | spot_waypoint_reached (void) | 
| float | stop_waypt_distance (bool same_lane) | 
| return distance to stop way-point, Infinite::distance if none | |
| bool | switch_to_passing_lane () | 
| switch to previously selected passing lane | |
| void | turn_signal_on (bool direction) | 
| void | turn_signals_both_on (void) | 
| set both turn signals on | |
| void | turn_signals_off (void) | 
| set both turn signals off | |
| float | uturn_distance (void) | 
| return distance to U-turn way-point, Infinite::distance if none. | |
| int | uturn_order_index (void) | 
| return index of U-turn exit in order->waypt array | |
| bool | uturn_waypt (unsigned windex) | 
| return true if waypt[windex] and waypt[windex+1] are a U-turn pair | |
| bool | zone_perimeter_reached (void) | 
| bool | zone_waypoint_reached (void) | 
| return true if zone way-point reached | |
| ~Course () | |
| Destructor. | |
| Public Attributes | |
| poly | aim_poly | 
| poly_list_t | passed_lane | 
| bool | passing_left | 
| poly_list_t | plan | 
| poly_list_t | polygons | 
| MapPose | start_pass_location | 
| poly | stop_poly | 
| WayPointNode | stop_waypt | 
| ZonePerimeterList | zones | 
| Private Member Functions | |
| Polar | head_for_waypt (float target_dist) | 
| head directly for next reachable way-point | |
| void | set_plan_waypts (void) | 
| set new plan way-points | |
| Private Attributes | |
| ElementID | adj_lane [2] | 
| poly_list_t | adj_polys [2] | 
| const Config * | config_ | 
| nav_msgs::Odometry * | estimate | 
| double | heading_change_ratio | 
| double | k_error | 
| double | k_int | 
| double | k_theta | 
| double | lane_change_secs | 
| double | last_error | 
| double | max_speed_for_sharp | 
| double | max_yaw_rate | 
| double | min_lane_steer_dist | 
| Navigator * | nav | 
| art_msgs::NavigatorState * | navdata | 
| bool | new_plan_lanes | 
| nav_msgs::Odometry * | odom | 
| art_msgs::Order * | order | 
| int | passing_lane | 
| ElementID | plan_waypt [art_msgs::Order::N_WAYPTS] | 
| int | poly_index | 
| PolyOps * | pops | 
| int | saved_replan_num | 
| ElementID | saved_waypt_id [art_msgs::Order::N_WAYPTS] | 
| double | spot_waypoint_radius | 
| double | spring_lookahead | 
| double | turning_latency | 
| int | verbose | 
| bool | waypoint_checked | 
| double | zone_waypoint_radius | 
| enum Course::direction_t | 
| Course::Course | ( | Navigator * | _nav, | 
| int | _verbose | ||
| ) | 
| Course::~Course | ( | ) |  [inline] | 
| void Course::begin_run_cycle | ( | void | ) | 
| mapxy_list_t Course::calculate_spot_points | ( | const std::vector< WayPointNode > & | new_waypts | ) | 
| void Course::configure | ( | ) | 
| void Course::desired_heading | ( | pilot_command_t & | pcmd, | 
| float | offset_ratio = 0.0 | ||
| ) | 
set heading for desired course
Set heading for desired course.
| pcmd[in,out] | pilot command to be published | 
| offset_ratio | 1.0 pushes the left side of the car to the left lane boundary, 0.0 to the center, -1.0 to the right. Larger offsets push the car outside the lane. | 
| float Course::distance_in_plan | ( | const MapPose & | from, | 
| const WayPointNode & | wp | ||
| ) | const | 
| float Course::distance_in_plan | ( | const MapPose & | from, | 
| const MapPose & | to | ||
| ) | const | 
| float Course::distance_in_plan | ( | const MapPose & | from, | 
| const MapXY & | to | ||
| ) | const | 
| void Course::end_run_cycle | ( | void | ) | 
| int Course::find_aim_polygon | ( | poly_list_t & | lane | ) | 
| bool Course::find_passing_lane | ( | void | ) | 
| void Course::find_travel_lane | ( | bool | rejoin | ) | 
| float Course::get_yaw_spring_system | ( | const Polar & | aim_polar, | 
| int | poly_id, | ||
| float | poly_heading, | ||
| float | max_yaw, | ||
| float | curr_velocity, | ||
| float | offset_ratio = 0.0 | ||
| ) | 
| Polar Course::head_for_waypt | ( | float | target_dist | ) |  [private] | 
| bool Course::in_lane | ( | const MapPose & | pose | ) | const  [inline] | 
| bool Course::in_poly_list | ( | const poly_list_t & | polys, | 
| const MapPose & | pose | ||
| ) | const  [inline] | 
| bool Course::lane_waypoint_reached | ( | void | ) | 
| void Course::lanes_message | ( | const art_msgs::ArtLanes & | lanes | ) | 
handle lanes message
Called from the driver ProcessMessage() handler when new lanes data arrive.
| lanes | pointer to the lanes message in the player message queue. Must copy the data before returning. | 
Handle lanes message.
Called from the topic subscription callback when new lanes data arrive.
| void Course::log | ( | const char * | str, | 
| const poly_list_t & | polys | ||
| ) | 
| float Course::max_speed_for_change_in_heading | ( | const float & | dheading, | 
| const float & | distance, | ||
| const float & | max, | ||
| const float & | max_yaw_rate | ||
| ) | 
| float Course::max_speed_for_slow_down | ( | const float & | final_speed, | 
| const float & | distance, | ||
| const float & | max, | ||
| const float & | max_deceleration | ||
| ) | 
| void Course::new_waypoint_reached | ( | ElementID | new_way | ) |  [inline] | 
| bool Course::new_waypts | ( | void | ) | 
| void Course::no_waypoint_reached | ( | void | ) |  [inline] | 
| bool Course::nqe_special | ( | int | i, | 
| int | j | ||
| ) | 
| bool Course::plan_valid | ( | void | ) |  [inline] | 
| ElementID Course::replan_roadblock | ( | void | ) | 
| void Course::reset | ( | void | ) | 
| bool Course::same_lane | ( | ElementID | id1, | 
| ElementID | id2 | ||
| ) |  [inline] | 
| void Course::set_plan_waypts | ( | void | ) |  [inline, private] | 
| void Course::signal_for_direction | ( | direction_t | direction | ) |  [inline] | 
| void Course::signal_pass | ( | void | ) |  [inline] | 
| void Course::signal_pass_return | ( | void | ) |  [inline] | 
| bool Course::special_waypt | ( | unsigned | windex | ) |  [inline] | 
| bool Course::spot_waypoint_reached | ( | void | ) | 
| float Course::stop_waypt_distance | ( | bool | same_lane | ) | 
return distance to stop way-point, Infinite::distance if none
exit: sets stop_waypt, if found
| void Course::turn_signal_on | ( | bool | direction | ) |  [inline] | 
| void Course::turn_signals_both_on | ( | void | ) |  [inline] | 
| void Course::turn_signals_off | ( | void | ) |  [inline] | 
| float Course::uturn_distance | ( | void | ) | 
return distance to U-turn way-point, Infinite::distance if none.
exit: sets stop_waypt to U-turn exit point, if found
| int Course::uturn_order_index | ( | void | ) | 
| bool Course::uturn_waypt | ( | unsigned | windex | ) | 
| bool Course::zone_perimeter_reached | ( | void | ) | 
| bool Course::zone_waypoint_reached | ( | void | ) | 
| ElementID Course::adj_lane[2]  [private] | 
| poly_list_t Course::adj_polys[2]  [private] | 
| const Config* Course::config_  [private] | 
| nav_msgs::Odometry* Course::estimate  [private] | 
| double Course::heading_change_ratio  [private] | 
| double Course::k_error  [private] | 
| double Course::k_int  [private] | 
| double Course::k_theta  [private] | 
| double Course::lane_change_secs  [private] | 
| double Course::last_error  [private] | 
| double Course::max_speed_for_sharp  [private] | 
| double Course::max_yaw_rate  [private] | 
| double Course::min_lane_steer_dist  [private] | 
| Navigator* Course::nav  [private] | 
| art_msgs::NavigatorState* Course::navdata  [private] | 
| bool Course::new_plan_lanes  [private] | 
| nav_msgs::Odometry* Course::odom  [private] | 
| art_msgs::Order* Course::order  [private] | 
| int Course::passing_lane  [private] | 
| ElementID Course::plan_waypt[art_msgs::Order::N_WAYPTS]  [private] | 
| int Course::poly_index  [private] | 
| PolyOps* Course::pops  [private] | 
| int Course::saved_replan_num  [private] | 
| double Course::spot_waypoint_radius  [private] | 
| double Course::spring_lookahead  [private] | 
| double Course::turning_latency  [private] | 
| int Course::verbose  [private] | 
| bool Course::waypoint_checked  [private] | 
| double Course::zone_waypoint_radius  [private] |