Public Member Functions | Private Member Functions | Private Attributes
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?
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.
art_msgs::Observation observation (art_msgs::Observation::_oid_type oid)
 return current observation state
bool observer_clear (art_msgs::Observation::_oid_type oid)
 return true when observer reports clear to go
void observers_message (const art_msgs::ObservationArrayConstPtr obs_msg)
 ObservationArray message callback.
 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::NavigatorStatenavdata
ros::Subscriber obs_sub_
art_msgs::ObservationArray obstate
nav_msgs::Odometry * odom
art_msgs::Orderorder
PolyOpspops
int verbose
bool was_stopped

Detailed Description

Navigator obstacle class.

Todo:

Add ROS-style ObstacleGrid input.

Add ART-style Observers input.

Definition at line 24 of file obstacle.h.


Constructor & Destructor Documentation

Obstacle::Obstacle ( Navigator _nav,
int  _verbose 
)

Constructor.

Definition at line 22 of file obstacle.cc.

Obstacle::~Obstacle ( ) [inline]

Destructor.

Definition at line 32 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 41 of file obstacle.h.

void Obstacle::blocked ( void  ) [inline]

mark car blocked, (re)start timeout.

Definition at line 47 of file obstacle.h.

is there a car approaching from ahead in our lane?

Definition at line 68 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 108 of file obstacle.cc.

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

Definition at line 145 of file obstacle.cc.

bool Obstacle::initialized ( void  ) [inline]

return true if class initialized

Definition at line 61 of file obstacle.h.

float Obstacle::maximum_range ( void  ) [inline]

maximum scan range accessor.

Definition at line 68 of file obstacle.h.

return current observation state

Definition at line 71 of file obstacle.h.

return true when observer reports clear to go

Definition at line 77 of file obstacle.h.

ObservationArray message callback.

Parameters:
obs_msgpointer to the observations message.

Definition at line 182 of file obstacle.cc.

return true when observer reports passing lane clear

Definition at line 199 of file obstacle.cc.

void Obstacle::reset ( void  )

reset obstacles.

Definition at line 208 of file obstacle.cc.

void Obstacle::unblocked ( void  ) [inline]

mark car not blocked, cancel timeout.

Definition at line 96 of file obstacle.h.

void Obstacle::update_blockage_state ( void  ) [inline]

update blockage timer state.

Definition at line 104 of file obstacle.h.


Member Data Documentation

Definition at line 132 of file obstacle.h.

const Config* Obstacle::config_ [private]

Definition at line 146 of file obstacle.h.

Definition at line 141 of file obstacle.h.

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

Definition at line 145 of file obstacle.h.

float Obstacle::max_range [private]

Definition at line 124 of file obstacle.h.

Definition at line 137 of file obstacle.h.

Definition at line 143 of file obstacle.h.

Definition at line 126 of file obstacle.h.

Definition at line 129 of file obstacle.h.

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

Definition at line 144 of file obstacle.h.

Definition at line 142 of file obstacle.h.

PolyOps* Obstacle::pops [private]

Definition at line 140 of file obstacle.h.

int Obstacle::verbose [private]

Definition at line 136 of file obstacle.h.

Definition at line 133 of file obstacle.h.


The documentation for this class was generated from the following files:


art_nav
Author(s): Austin Robot Technology, Jack O'Quin
autogenerated on Fri Jan 3 2014 11:08:43