Obstacle Class Reference

Navigator obstacle class. More...

#include <obstacle.h>

List of all members.

Public Member Functions

bool blockage_timeout (void)
 update blockage_timer (do once per run cycle)
void blocked (void)
 mark car blocked, (re)start timeout.
bool car_approaching ()
 is there a car approaching from ahead in our lane?
float closest_ahead_in_plan (void)
 return distance to closest obstacle ahead in course plan
void closest_in_lane (const poly_list_t &lane, float &ahead, float &behind)
bool initialized (void)
 return true if class initialized
float maximum_range (void)
 maximum scan range accessor.
Observation observation (Observation::_oid_type oid)
 return current observation state
bool observer_clear (Observation::_oid_type oid)
 return true when observer reports clear to go
void observers_message (Observers *obs_msg)
 handle observers driver message
 Obstacle (Navigator *_nav, int _verbose)
 Constructor.
bool passing_lane_clear (void)
 return true when observer reports passing lane clear
void reset (void)
 reset obstacles.
void unblocked (void)
 mark car not blocked, cancel timeout.
void update_blockage_state (void)
 update blockage timer state.
 ~Obstacle ()
 Destructor.

Private Member Functions

bool in_lane (MapXY location, const poly_list_t &lane, int start_index)

Private Attributes

NavTimerblockage_timer
const Configconfig_
Coursecourse
nav_msgs::Odometry * estimate
float max_range
Navigatornav
art_msgs::NavigatorState * navdata
Observers obstate
nav_msgs::Odometry * odom
art_msgs::Order * order
PolyOps * pops
Observers prev_obstate
int verbose
bool was_stopped

Detailed Description

Navigator obstacle class.

Todo:

Add ROS-style ObstacleGrid input.

Add ART-style Observers input.

Definition at line 29 of file obstacle.h.


Constructor & Destructor Documentation

Obstacle::Obstacle ( Navigator _nav,
int  _verbose 
)

Constructor.

Definition at line 19 of file obstacle.cc.

Obstacle::~Obstacle (  )  [inline]

Destructor.

Definition at line 37 of file obstacle.h.


Member Function Documentation

bool Obstacle::blockage_timeout ( void   )  [inline]

update blockage_timer (do once per run cycle)

Returns:
true if timeout reached

Definition at line 46 of file obstacle.h.

void Obstacle::blocked ( void   )  [inline]

mark car blocked, (re)start timeout.

Definition at line 52 of file obstacle.h.

bool Obstacle::car_approaching (  ) 

is there a car approaching from ahead in our lane?

Definition at line 57 of file obstacle.cc.

float Obstacle::closest_ahead_in_plan ( void   ) 

return distance to closest obstacle ahead in course plan

Definition at line 87 of file obstacle.cc.

void Obstacle::closest_in_lane ( const poly_list_t &  lane,
float &  ahead,
float &  behind 
)

Return distances of closest obstacles ahead and behind in a lane.

Definition at line 146 of file obstacle.cc.

bool Obstacle::in_lane ( MapXY  location,
const poly_list_t &  lane,
int  start_index 
) [private]

Definition at line 183 of file obstacle.cc.

bool Obstacle::initialized ( void   )  [inline]

return true if class initialized

Definition at line 69 of file obstacle.h.

float Obstacle::maximum_range ( void   )  [inline]

maximum scan range accessor.

Definition at line 76 of file obstacle.h.

Observation Obstacle::observation ( Observation::_oid_type  oid  )  [inline]

return current observation state

Definition at line 79 of file obstacle.h.

bool Obstacle::observer_clear ( Observation::_oid_type  oid  )  [inline]

return true when observer reports clear to go

Definition at line 85 of file obstacle.h.

void Obstacle::observers_message ( Observers *  obs_msg  ) 

handle observers driver message

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

Parameters:
hdr the player message header pointer
obs_msg pointer to the observer state message struct in the player message queue. Must copy the data before returning.

Definition at line 220 of file obstacle.cc.

bool Obstacle::passing_lane_clear ( void   ) 

return true when observer reports passing lane clear

Definition at line 259 of file obstacle.cc.

void Obstacle::reset ( void   ) 

reset obstacles.

Definition at line 268 of file obstacle.cc.

void Obstacle::unblocked ( void   )  [inline]

mark car not blocked, cancel timeout.

Definition at line 113 of file obstacle.h.

void Obstacle::update_blockage_state ( void   )  [inline]

update blockage timer state.

Definition at line 121 of file obstacle.h.


Member Data Documentation

Definition at line 148 of file obstacle.h.

const Config* Obstacle::config_ [private]

Definition at line 162 of file obstacle.h.

Definition at line 157 of file obstacle.h.

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

Definition at line 161 of file obstacle.h.

float Obstacle::max_range [private]

Definition at line 141 of file obstacle.h.

Definition at line 153 of file obstacle.h.

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

Definition at line 159 of file obstacle.h.

Observers Obstacle::obstate [private]

Definition at line 144 of file obstacle.h.

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

Definition at line 160 of file obstacle.h.

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

Definition at line 158 of file obstacle.h.

PolyOps* Obstacle::pops [private]

Definition at line 156 of file obstacle.h.

Observers Obstacle::prev_obstate [private]

Definition at line 145 of file obstacle.h.

int Obstacle::verbose [private]

Definition at line 152 of file obstacle.h.

bool Obstacle::was_stopped [private]

Definition at line 149 of file obstacle.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