$search

observers::Observer Class Reference

Observers base class. More...

#include <observer.h>

Inheritance diagram for observers::Observer:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
art_msgs::Observation::_oid_type 
Oid_t

Public Member Functions

art_msgs::ArtLanes getObstaclesInLane (art_msgs::ArtLanes obstacles, art_msgs::ArtLanes lane_quads)
 Observer (art_observers::ObserversConfig &config, Oid_t id, const std::string &name)
bool pointInLane (float x, float y, art_msgs::ArtLanes lane)
virtual art_msgs::Observation update (const art_msgs::ArtLanes &local_map, const art_msgs::ArtLanes &obstacles, MapPose pose)=0
 ~Observer ()

Protected Attributes

art_observers::ObserversConfig config_
art_msgs::Observation observation_

Detailed Description

Observers base class.

Definition at line 30 of file observer.h.


Member Typedef Documentation

Shorter typedef for observer ID

Definition at line 35 of file observer.h.


Constructor & Destructor Documentation

observers::Observer::Observer ( art_observers::ObserversConfig config,
Oid_t  id,
const std::string &  name 
) [inline]

Constructor.

Parameters:
config configuration structure
id observer ID
name observer name

Definition at line 43 of file observer.h.

observers::Observer::~Observer (  ) 

Definition at line 20 of file observer.cc.


Member Function Documentation

art_msgs::ArtLanes observers::Observer::getObstaclesInLane ( art_msgs::ArtLanes  obstacles,
art_msgs::ArtLanes  lane_quads 
)

Definition at line 24 of file observer.cc.

bool observers::Observer::pointInLane ( float  x,
float  y,
art_msgs::ArtLanes  lane 
)

Used by all observers to get obstacles in polygons of interest

Todo:
move these out of this pure virtual base class.
virtual art_msgs::Observation observers::Observer::update ( const art_msgs::ArtLanes local_map,
const art_msgs::ArtLanes obstacles,
MapPose  pose 
) [pure virtual]

Generic observer update function.

Called whenever there are new obstacle data, assuming the local_map is also available.

Parameters:
robot_quad quadrilateral containing the robot
local_map road map lanes within range of the robot
obstacles local map quads currently containing obstacles
pose current pose of robot
Todo:
Make pure virtual once deprecated version is deleted.

Implemented in observers::AdjacentLeft, observers::AdjacentRight, observers::NearestBackward, and observers::NearestForward.


Member Data Documentation

Definition at line 85 of file observer.h.

Definition at line 84 of file observer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


art_observers
Author(s): Michael Quinlan, Jack O'Quin, Corbyn Salisbury
autogenerated on Fri Mar 1 14:13:59 2013