Course Class Reference

Navigator course planning class. More...

#include <course.h>

List of all members.

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 ()
mapxy_list_t calculate_spot_points (const std::vector< WayPointNode > &new_waypts)
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 MapXY &to) const
float distance_in_plan (const MapPose &from, const MapPose &to) const
float distance_in_plan (const MapPose &from, const WayPointNode &wp) 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 Configconfig_
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
Navigatornav
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

Detailed Description

Navigator course planning class.

Definition at line 25 of file course.h.


Member Enumeration Documentation

Enumerator:
Right 
Straight 
Left 

Definition at line 30 of file course.h.


Constructor & Destructor Documentation

Course::Course ( Navigator _nav,
int  _verbose 
)

Constructor.

Todo:
Use ROS tf instead of art_map/rotate_translate_transform

Definition at line 27 of file course.cc.

Course::~Course (  )  [inline]

Destructor.

Definition at line 40 of file course.h.


Member Function Documentation

void Course::begin_run_cycle ( void   ) 

Course class initialization for run state cycle.

Definition at line 60 of file course.cc.

mapxy_list_t Course::calculate_spot_points (  ) 
mapxy_list_t Course::calculate_spot_points ( const std::vector< WayPointNode > &  new_waypts  ) 
mapxy_list_t Course::calculate_zone_barrier_points (  ) 
void Course::configure (  ) 

set configuration variables.

Definition at line 119 of file course.cc.

bool Course::curr_spot (  ) 

Definition at line 1499 of file course.cc.

void Course::desired_heading ( pilot_command_t pcmd,
float  offset_ratio = 0.0 
)

set heading for desired course

Set heading for desired course.

Precondition:
plan contains desired polygon path to follow
Parameters:
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.

Definition at line 220 of file course.cc.

float Course::distance_in_plan ( const MapPose &  from,
const MapXY &  to 
) const

return distance in a lane to a pose

Definition at line 424 of file course.cc.

float Course::distance_in_plan ( const MapPose &  from,
const MapPose &  to 
) const

return distance in a lane to a pose

Definition at line 416 of file course.cc.

float Course::distance_in_plan ( const MapPose &  from,
const WayPointNode &  wp 
) const

return distance in a lane to a way-point

Definition at line 407 of file course.cc.

void Course::end_run_cycle ( void   ) 

Course class termination for run state cycle.

Definition at line 439 of file course.cc.

int Course::find_aim_polygon ( poly_list_t &  lane  ) 

find the index in lane of a polygon to aim for ahead of the car (returns -1 if none)

Definition at line 453 of file course.cc.

bool Course::find_passing_lane ( void   ) 

Find a passing lane through the polygons.

Definition at line 538 of file course.cc.

void Course::find_travel_lane ( bool  rejoin  ) 

Find a path in the travel lane to the next few way-points.

Definition at line 683 of file course.cc.

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 
)

Definition at line 1369 of file course.cc.

Polar Course::head_for_waypt ( float  target_dist  )  [private]

head directly for next reachable way-point

Definition at line 774 of file course.cc.

bool Course::in_lane ( const MapPose &  pose  )  const [inline]

return true if pose is in the current travel lane

Definition at line 78 of file course.h.

bool Course::in_poly_list ( const poly_list_t &  polys,
const MapPose &  pose 
) const [inline]

return true if pose is in the polys list

Definition at line 84 of file course.h.

Course::direction_t Course::intersection_direction ( void   ) 

return intersection crossing direction

Definition at line 1034 of file course.cc.

Course::direction_t Course::lane_change_direction ( void   ) 

return lane change direction

Definition at line 813 of file course.cc.

bool Course::lane_waypoint_reached ( void   ) 

return true if lane way-point reached

Definition at line 840 of file course.cc.

void Course::lanes_message ( const art_msgs::ArtLanes &  lanes  ) 

handle lanes message

Called from the driver ProcessMessage() handler when new lanes data arrive.

Parameters:
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.

Definition at line 915 of file course.cc.

void Course::log ( const char *  str,
const poly_list_t &  polys 
)

log a vector of polygons

Definition at line 932 of file course.cc.

float Course::max_speed_for_change_in_heading ( const float &  dheading,
const float &  distance,
const float &  max,
const float &  max_yaw_rate 
)

Definition at line 1346 of file course.cc.

float Course::max_speed_for_slow_down ( const float &  final_speed,
const float &  distance,
const float &  max,
const float &  max_deceleration 
)

Definition at line 1322 of file course.cc.

void Course::new_waypoint_reached ( ElementID  new_way  )  [inline]

confirm that the next way-point was reached

Definition at line 112 of file course.h.

bool Course::new_waypts ( void   ) 

return true if current order does not match saved way-points

Definition at line 973 of file course.cc.

void Course::no_waypoint_reached ( void   )  [inline]

confirm that no way-point was reached

Definition at line 124 of file course.h.

bool Course::nqe_special ( int  i,
int  j 
)

Definition at line 1647 of file course.cc.

bool Course::plan_valid ( void   )  [inline]

return whether the current plan is still valid

Technically, a plan is no longer valid after we receive new polygons, but that is currently ignored for simplicity.

Definition at line 134 of file course.h.

ElementID Course::replan_roadblock ( void   ) 

replan after road block

exit: saves current order way-points returns: ElementID of way-point from which to replan (null ElementID if unable to find alternate)

Definition at line 1001 of file course.cc.

void Course::reset ( void   ) 

reset course

Definition at line 987 of file course.cc.

bool Course::same_lane ( ElementID  id1,
ElementID  id2 
) [inline]

are id1 and id2 in the same lane?

Beware of a segment that loops back to itself. In that case, the lane is the same, but the way-point numbers decrease.

Definition at line 162 of file course.h.

void Course::set_plan_waypts ( void   )  [inline, private]

set new plan way-points

Definition at line 361 of file course.h.

void Course::signal_for_direction ( direction_t  direction  )  [inline]

set turn signal based on direction

Definition at line 197 of file course.h.

void Course::signal_pass ( void   )  [inline]

set turn signal for passing

Definition at line 174 of file course.h.

void Course::signal_pass_return ( void   )  [inline]

set turn signal for return from passing

Definition at line 180 of file course.h.

bool Course::special_waypt ( unsigned  windex  )  [inline]

special way-point predicate

Parameters:
windex an index in the order->waypt[] array.
Returns:
true for a special way-point (stop, or U-turn)

Definition at line 190 of file course.h.

bool Course::spot_ahead (  ) 

Definition at line 1486 of file course.cc.

bool Course::spot_waypoint_reached ( void   ) 

Definition at line 1293 of file course.cc.

float Course::stop_waypt_distance ( bool  same_lane  ) 

return distance to stop way-point, Infinite::distance if none

exit: sets stop_waypt, if found

Definition at line 1068 of file course.cc.

bool Course::switch_to_passing_lane (  ) 

switch to previously selected passing lane

Definition at line 1110 of file course.cc.

void Course::turn_signal_on ( bool  direction  )  [inline]

request a turn signal on (direction true for left turns)

Definition at line 238 of file course.h.

void Course::turn_signals_both_on ( void   )  [inline]

set both turn signals on

Definition at line 214 of file course.h.

void Course::turn_signals_off ( void   )  [inline]

set both turn signals off

Definition at line 226 of file course.h.

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

Definition at line 1158 of file course.cc.

int Course::uturn_order_index ( void   ) 

return index of U-turn exit in order->waypt array

Definition at line 1188 of file course.cc.

bool Course::uturn_waypt ( unsigned  windex  ) 

return true if waypt[windex] and waypt[windex+1] are a U-turn pair

Definition at line 1203 of file course.cc.

bool Course::zone_perimeter_reached ( void   ) 

Definition at line 1249 of file course.cc.

bool Course::zone_waypoint_reached ( void   ) 

return true if zone way-point reached

Definition at line 1219 of file course.cc.


Member Data Documentation

ElementID Course::adj_lane[2] [private]

Definition at line 318 of file course.h.

poly_list_t Course::adj_polys[2] [private]

Definition at line 319 of file course.h.

Definition at line 278 of file course.h.

const Config* Course::config_ [private]

Definition at line 355 of file course.h.

nav_msgs::Odometry* Course::estimate [private]

Definition at line 354 of file course.h.

double Course::heading_change_ratio [private]

Definition at line 327 of file course.h.

double Course::k_error [private]

Definition at line 328 of file course.h.

double Course::k_int [private]

Definition at line 329 of file course.h.

double Course::k_theta [private]

Definition at line 330 of file course.h.

double Course::lane_change_secs [private]

Definition at line 331 of file course.h.

double Course::last_error [private]

Definition at line 333 of file course.h.

double Course::max_speed_for_sharp [private]

Definition at line 334 of file course.h.

double Course::max_yaw_rate [private]

Definition at line 335 of file course.h.

double Course::min_lane_steer_dist [private]

Definition at line 337 of file course.h.

Navigator* Course::nav [private]

Definition at line 347 of file course.h.

art_msgs::NavigatorState* Course::navdata [private]

Definition at line 352 of file course.h.

bool Course::new_plan_lanes [private]

Definition at line 313 of file course.h.

nav_msgs::Odometry* Course::odom [private]

Definition at line 353 of file course.h.

art_msgs::Order* Course::order [private]

Definition at line 351 of file course.h.

poly_list_t Course::passed_lane

Definition at line 272 of file course.h.

int Course::passing_lane [private]

Definition at line 320 of file course.h.

Definition at line 273 of file course.h.

poly_list_t Course::plan

Definition at line 270 of file course.h.

ElementID Course::plan_waypt[art_msgs::Order::N_WAYPTS] [private]

Definition at line 312 of file course.h.

int Course::poly_index [private]

Definition at line 315 of file course.h.

poly_list_t Course::polygons

Definition at line 269 of file course.h.

PolyOps* Course::pops [private]

Definition at line 350 of file course.h.

int Course::saved_replan_num [private]

Definition at line 324 of file course.h.

ElementID Course::saved_waypt_id[art_msgs::Order::N_WAYPTS] [private]

Definition at line 323 of file course.h.

double Course::spot_waypoint_radius [private]

Definition at line 338 of file course.h.

double Course::spring_lookahead [private]

Definition at line 339 of file course.h.

Definition at line 274 of file course.h.

Definition at line 277 of file course.h.

WayPointNode Course::stop_waypt

Definition at line 276 of file course.h.

double Course::turning_latency [private]

Definition at line 340 of file course.h.

int Course::verbose [private]

Definition at line 346 of file course.h.

bool Course::waypoint_checked [private]

Definition at line 314 of file course.h.

double Course::zone_waypoint_radius [private]

Definition at line 343 of file course.h.

ZonePerimeterList Course::zones

Definition at line 280 of file course.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


art_nav
Author(s): Austin Robot Technology, Jack O'Quin
autogenerated on Fri Jan 11 10:05:40 2013