lobot::Scan Class Reference

An encapsulation of a laser range finder scan. More...

#include <Robots/LoBot/slam/LoScanMatch.H>

Collaboration diagram for lobot::Scan:
Collaboration graph
[legend]

List of all members.

Classes

class  RangeReading

Public Member Functions

 ~Scan ()
 Clean-up.

 Scan (const Pose &, const std::vector< int > &)
 Scan (const Pose &, const std::vector< float > &)

float x () const
 Various accessors.
float y () const
float theta () const
RangeReadingoperator[] (int i)
const RangeReadingoperator[] (int i) const

Detailed Description

An encapsulation of a laser range finder scan.

This class holds the range readings made by lobot's laser range finder in both polar and Cartesian form. It also records the robot's pose corresponding to those readings.

The scan matching algorithm takes two instances of this class and returns the transformation required to "convert" one scan to the other.

Definition at line 87 of file LoScanMatch.H.


Constructor & Destructor Documentation

lobot::Scan::Scan ( const Pose P,
const std::vector< int > &  R 
)

When a scan object is created, it should be given the pose and a vector containing the range readings in polar form. The constructor will take care of deriving the Cartesian coordinates for each distance reading from the given pose and the polar ranges.

Definition at line 230 of file LoScanMatch.C.

References transform().

lobot::Scan::~Scan (  ) 

Clean-up.

Definition at line 247 of file LoScanMatch.C.


Member Function Documentation

float lobot::Scan::x (  )  const [inline]

Various accessors.

Definition at line 130 of file LoScanMatch.H.

References lobot::Pose::x().


The documentation for this class was generated from the following files:
Generated on Sun May 8 08:30:45 2011 for iLab Neuromorphic Vision Toolkit by  doxygen 1.6.3