00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #ifndef _OBSTACLE_HH_
00012 #define _OBSTACLE_HH_
00013
00014 #include <vector>
00015 #include "ntimer.h"
00016
00017 #include <art_msgs/Observers.h>
00018
00019
00020
00021 using art_msgs::Observers;
00022 using art_msgs::Observation;
00023
00029 class Obstacle
00030 {
00031 public:
00032
00034 Obstacle(Navigator *_nav, int _verbose);
00035
00037 ~Obstacle()
00038 {
00039 delete blockage_timer;
00040 };
00041
00046 bool blockage_timeout(void)
00047 {
00048 return blockage_timer->Check();
00049 }
00050
00052 void blocked(void)
00053 {
00054 if (verbose >= 5)
00055 ART_MSG(3, "Starting blockage timer");
00056 blockage_timer->Start(config_->blockage_timeout_secs);
00057 }
00058
00060 bool car_approaching();
00061
00063 float closest_ahead_in_plan(void);
00064
00066 void closest_in_lane(const poly_list_t &lane, float &ahead, float &behind);
00067
00069 bool initialized(void)
00070 {
00071
00072 return true;
00073 };
00074
00076 float maximum_range(void) {return max_range;}
00077
00079 Observation observation(Observation::_oid_type oid)
00080 {
00081 return obstate.obs[oid];
00082 }
00083
00085 bool observer_clear(Observation::_oid_type oid)
00086 {
00087 bool clear = obstate.obs[oid].clear && obstate.obs[oid].applicable;
00088
00089
00090 if (!clear)
00091 blocked();
00092 return clear;
00093 }
00094
00104 void observers_message(Observers *obs_msg);
00105
00107 bool passing_lane_clear(void);
00108
00110 void reset(void);
00111
00113 void unblocked(void)
00114 {
00115 if (verbose >= 5)
00116 ART_MSG(3, "Canceling blockage timer");
00117 blockage_timer->Cancel();
00118 }
00119
00121 void update_blockage_state(void)
00122 {
00123 if (navdata->stopped != was_stopped ||
00124 !navdata->stopped)
00125 {
00126 if (navdata->stopped)
00127 blocked();
00128 else
00129 unblocked();
00130 if (verbose >= 4 &&
00131 navdata->stopped != was_stopped)
00132 ART_MSG(8, "vehicle %s moving",
00133 (navdata->stopped? "stopped": "started"));
00134 was_stopped = navdata->stopped;
00135 }
00136 }
00137
00138 private:
00139
00140
00141 float max_range;
00142
00143
00144 Observers obstate;
00145 Observers prev_obstate;
00146
00147
00148 NavTimer *blockage_timer;
00149 bool was_stopped;
00150
00151
00152 int verbose;
00153 Navigator *nav;
00154
00155
00156 PolyOps* pops;
00157 Course* course;
00158 art_msgs::Order *order;
00159 art_msgs::NavigatorState *navdata;
00160 nav_msgs::Odometry *odom;
00161 nav_msgs::Odometry *estimate;
00162 const Config *config_;
00163
00164
00165 bool in_lane(MapXY location, const poly_list_t &lane, int start_index);
00166
00167 #if 0 // ignoring obstacles at the moment
00168
00169 float laser_scan_bearing(unsigned index, const player_laser_data_t &scan)
00170 {
00171 return scan.min_angle + index * scan.resolution;
00172 }
00173 unsigned laser_scan_index(float bearing, const player_laser_data_t &scan)
00174 {
00175 unsigned index =
00176 (unsigned) rintf((bearing - scan.min_angle) / scan.resolution);
00177 if (index < 0)
00178 index = 0;
00179 else if (index > scan.ranges_count)
00180 index = scan.ranges_count;
00181 return index;
00182 }
00183 #endif // ignoring obstacles at the moment
00184 };
00185
00186 #endif // _OBSTACLE_HH_