00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 #ifndef _COURSE_HH_
00013 #define _COURSE_HH_
00014
00015 #include <vector>
00016
00017 #include <art/infinity.h>
00018 #include <art_msgs/ArtLanes.h>
00019 #include <art_map/coordinates.h>
00020 #include <art_map/zones.h>
00021
00022 #include "Controller.h"
00023
00025 class Course
00026 {
00027 public:
00028
00029
00030 typedef enum {
00031 Right = -1,
00032 Straight = 0,
00033 Left = 1
00034 } direction_t;
00035
00037 Course(Navigator *_nav, int _verbose);
00038
00040 ~Course() {};
00041
00043 void begin_run_cycle(void);
00044
00046 void configure();
00047
00049 void desired_heading(pilot_command_t &pcmd, float offset_ratio = 0.0);
00050
00052 float distance_in_plan(const MapPose &from,
00053 const WayPointNode &wp) const;
00054
00056 float distance_in_plan(const MapPose &from,
00057 const MapPose &to) const;
00058
00060 float distance_in_plan(const MapPose &from,
00061 const MapXY &to) const;
00062
00064 void end_run_cycle(void);
00065
00069 int find_aim_polygon(poly_list_t &lane);
00070
00072 bool find_passing_lane(void);
00073
00075 void find_travel_lane(bool rejoin);
00076
00078 bool in_lane(const MapPose &pose) const
00079 {
00080 return in_poly_list(plan, pose);
00081 }
00082
00084 bool in_poly_list(const poly_list_t &polys, const MapPose &pose) const
00085 {
00086 return (pops->getContainingPoly(polys, pose) >= 0);
00087 }
00088
00090 direction_t intersection_direction(void);
00091
00093 direction_t lane_change_direction(void);
00094
00096 bool lane_waypoint_reached(void);
00097
00106 void lanes_message(const art_msgs::ArtLanes &lanes);
00107
00109 void log(const char *str, const poly_list_t &polys);
00110
00112 void new_waypoint_reached(ElementID new_way)
00113 {
00114 waypoint_checked = true;
00115 navdata->last_waypt = new_way.toMapID();
00116 ROS_DEBUG_STREAM("reached waypoint %s" << new_way.name().str);
00117 };
00118
00121 bool new_waypts(void);
00122
00124 void no_waypoint_reached(void)
00125 {
00126 waypoint_checked = true;
00127 };
00128
00134 bool plan_valid(void)
00135 {
00136
00137 for (int i = 0; i < Order::N_WAYPTS; ++i)
00138 {
00139 if (plan_waypt[i] != order->waypt[i].id)
00140 return false;
00141 }
00142 return (!plan.empty()
00143 && !new_plan_lanes);
00144 }
00145
00152 ElementID replan_roadblock(void);
00153
00155 void reset(void);
00156
00162 bool same_lane(ElementID id1, ElementID id2)
00163 {
00164 return (id1.same_lane(id2) && id1.pt <= id2.pt);
00165 }
00166
00171 float stop_waypt_distance(bool same_lane);
00172
00174 void signal_pass(void)
00175 {
00176 turn_signal_on(passing_left);
00177 }
00178
00180 void signal_pass_return(void)
00181 {
00182 turn_signal_on(!passing_left);
00183 }
00184
00190 bool special_waypt(unsigned windex)
00191 {
00192 return (order->waypt[windex].is_stop
00193 || uturn_waypt(windex));
00194 }
00195
00197 void signal_for_direction(direction_t direction)
00198 {
00199 if (direction == Straight)
00200 {
00201 turn_signals_off();
00202 }
00203 else
00204 {
00205
00206 turn_signal_on(direction == Left);
00207 }
00208 }
00209
00211 bool switch_to_passing_lane();
00212
00214 void turn_signals_both_on(void)
00215 {
00216 if (navdata->signal_left || navdata->signal_right)
00217 {
00218 navdata->signal_left = true;
00219 navdata->signal_right = true;
00220 if (verbose >= 3)
00221 ART_MSG(7, "setting both turn signals on");
00222 }
00223 }
00224
00226 void turn_signals_off(void)
00227 {
00228 if (navdata->signal_left || navdata->signal_right)
00229 {
00230 navdata->signal_left = false;
00231 navdata->signal_right = false;
00232 if (verbose >= 3)
00233 ART_MSG(7, "setting turn signals off");
00234 }
00235 }
00236
00238 void turn_signal_on(bool direction)
00239 {
00240 if (navdata->signal_left != direction
00241 || navdata->signal_right != !direction)
00242 {
00243 navdata->signal_left = direction;
00244 navdata->signal_right = !direction;
00245 if (verbose >= 3)
00246 ART_MSG(7, "signalling %s", (direction? "left": "right"));
00247 }
00248 }
00249
00254 float uturn_distance(void);
00255
00257 int uturn_order_index(void);
00258
00261 bool uturn_waypt(unsigned windex);
00262
00264 bool zone_waypoint_reached(void);
00265 bool zone_perimeter_reached(void);
00266 bool spot_waypoint_reached(void);
00267
00268
00269 poly_list_t polygons;
00270 poly_list_t plan;
00271
00272 poly_list_t passed_lane;
00273 bool passing_left;
00274 MapPose start_pass_location;
00275
00276 WayPointNode stop_waypt;
00277 poly stop_poly;
00278 poly aim_poly;
00279
00280 ZonePerimeterList zones;
00281
00282
00283 float max_speed_for_slow_down(const float& final_speed,
00284 const float& distance,
00285 const float& max,
00286 const float& max_deceleration);
00287
00288 float max_speed_for_change_in_heading(const float& dheading,
00289 const float& distance,
00290 const float& max,
00291 const float& max_yaw_rate);
00292
00293 float get_yaw_spring_system(const Polar& aim_polar, int poly_id,
00294 float poly_heading,
00295 float max_yaw, float curr_velocity,
00296 float offset_ratio = 0.0);
00297
00298 bool spot_ahead();
00299 mapxy_list_t calculate_spot_points(const std::vector<WayPointNode>
00300 &new_waypts);
00301 mapxy_list_t calculate_spot_points();
00302 mapxy_list_t calculate_zone_barrier_points();
00303 bool curr_spot();
00304
00305 bool nqe_special(int i, int j);
00306
00307 private:
00308
00309
00310
00311
00312 ElementID plan_waypt[art_msgs::Order::N_WAYPTS];
00313 bool new_plan_lanes;
00314 bool waypoint_checked;
00315 int poly_index;
00316
00317
00318 ElementID adj_lane[2];
00319 poly_list_t adj_polys[2];
00320 int passing_lane;
00321
00322
00323 ElementID saved_waypt_id[art_msgs::Order::N_WAYPTS];
00324 int saved_replan_num;
00325
00326
00327 double heading_change_ratio;
00328 double k_error;
00329 double k_int;
00330 double k_theta;
00331 double lane_change_secs;
00332
00333 double last_error;
00334 double max_speed_for_sharp;
00335 double max_yaw_rate;
00336
00337 double min_lane_steer_dist;
00338 double spot_waypoint_radius;
00339 double spring_lookahead;
00340 double turning_latency;
00341
00342
00343 double zone_waypoint_radius;
00344
00345
00346 int verbose;
00347 Navigator *nav;
00348
00349
00350 PolyOps* pops;
00351 art_msgs::Order *order;
00352 art_msgs::NavigatorState *navdata;
00353 nav_msgs::Odometry *odom;
00354 nav_msgs::Odometry *estimate;
00355 const Config *config_;
00356
00358 Polar head_for_waypt(float target_dist);
00359
00361 void set_plan_waypts(void)
00362 {
00363 for (int i = 0; i < Order::N_WAYPTS; ++i)
00364 plan_waypt[i] = order->waypt[i].id;
00365 }
00366
00367
00368 };
00369
00370 #endif // _COURSE_HH_