$search
Navigator obstacle class. More...
#include <obstacle.h>
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 | |
NavTimer * | blockage_timer |
const Config * | config_ |
Course * | course |
nav_msgs::Odometry * | estimate |
float | max_range |
Navigator * | nav |
art_msgs::NavigatorState * | navdata |
ros::Subscriber | obs_sub_ |
art_msgs::ObservationArray | obstate |
nav_msgs::Odometry * | odom |
art_msgs::Order * | order |
PolyOps * | pops |
int | verbose |
bool | was_stopped |
Navigator obstacle class.
Add ROS-style ObstacleGrid input.
Add ART-style Observers input.
Definition at line 24 of file obstacle.h.
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.
bool Obstacle::blockage_timeout | ( | void | ) | [inline] |
update blockage_timer (do once per run cycle)
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.
bool Obstacle::car_approaching | ( | ) |
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.
art_msgs::Observation Obstacle::observation | ( | art_msgs::Observation::_oid_type | oid | ) | [inline] |
return current observation state
Definition at line 71 of file obstacle.h.
bool Obstacle::observer_clear | ( | art_msgs::Observation::_oid_type | oid | ) | [inline] |
return true when observer reports clear to go
Definition at line 77 of file obstacle.h.
void Obstacle::observers_message | ( | const art_msgs::ObservationArrayConstPtr | obs_msg | ) |
ObservationArray message callback.
obs_msg | pointer to the observations message. |
Definition at line 182 of file obstacle.cc.
bool Obstacle::passing_lane_clear | ( | void | ) |
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.
NavTimer* Obstacle::blockage_timer [private] |
Definition at line 132 of file obstacle.h.
const Config* Obstacle::config_ [private] |
Definition at line 146 of file obstacle.h.
Course* Obstacle::course [private] |
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.
Navigator* Obstacle::nav [private] |
Definition at line 137 of file obstacle.h.
art_msgs::NavigatorState* Obstacle::navdata [private] |
Definition at line 143 of file obstacle.h.
ros::Subscriber Obstacle::obs_sub_ [private] |
Definition at line 126 of file obstacle.h.
art_msgs::ObservationArray Obstacle::obstate [private] |
Definition at line 129 of file obstacle.h.
nav_msgs::Odometry* Obstacle::odom [private] |
Definition at line 144 of file obstacle.h.
art_msgs::Order* Obstacle::order [private] |
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.
bool Obstacle::was_stopped [private] |
Definition at line 133 of file obstacle.h.