karto::LaserRangeFinder Class Reference

#include <Karto.h>

Inheritance diagram for karto::LaserRangeFinder:
Inheritance graph
[legend]

List of all members.

Public Member Functions

kt_double GetAngularResolution () const
kt_double GetMaximumAngle () const
kt_double GetMaximumRange () const
kt_double GetMinimumAngle () const
kt_double GetMinimumRange () const
kt_int32u GetNumberOfRangeReadings () const
const PointVectorDouble GetPointReadings (LocalizedRangeScan *pLocalizedRangeScan, CoordinateConverter *pCoordinateConverter, kt_bool ignoreThresholdPoints=true, kt_bool flipY=false) const
kt_double GetRangeThreshold () const
kt_int32s GetType ()
 KARTO_Object (LaserRangeFinder) public
void SetAngularResolution (kt_double angularResolution)
void SetMaximumAngle (kt_double maximumAngle)
void SetMaximumRange (kt_double maximumRange)
void SetMinimumAngle (kt_double minimumAngle)
void SetMinimumRange (kt_double minimumRange)
void SetRangeThreshold (kt_double rangeThreshold)
virtual kt_bool Validate (SensorData *pSensorData)
virtual kt_bool Validate ()

Static Public Member Functions

static LaserRangeFinderCreateLaserRangeFinder (LaserRangeFinderType type, const Name &rName)

Private Member Functions

 LaserRangeFinder (const LaserRangeFinder &)
 LaserRangeFinder (const Name &rName)
const LaserRangeFinderoperator= (const LaserRangeFinder &)
void Update ()

Private Attributes

kt_int32u m_NumberOfRangeReadings
Parameter< kt_double > * m_pAngularResolution
Parameter< kt_double > * m_pMaximumAngle
Parameter< kt_double > * m_pMaximumRange
Parameter< kt_double > * m_pMinimumAngle
Parameter< kt_double > * m_pMinimumRange
Parameter< kt_double > * m_pRangeThreshold
ParameterEnumm_pType

Detailed Description

The LaserRangeFinder defines a laser sensor that provides the pose offset position of a localized range scan relative to the robot. The user can set an offset pose for the sensor relative to the robot coordinate system. If no value is provided by the user, the sensor is set to be at the origin of the robot coordinate system. The LaserRangeFinder contains parameters for physical laser sensor used by the mapper for scan matching Also contains information about the maximum range of the sensor and provides a threshold for limiting the range of readings. The optimal value for the range threshold depends on the angular resolution of the scan and the desired map resolution. RangeThreshold should be set as large as possible while still providing "solid" coverage between consecutive range readings. The diagram below illustrates the relationship between map resolution and the range threshold.

Definition at line 3560 of file Karto.h.


Constructor & Destructor Documentation

karto::LaserRangeFinder::LaserRangeFinder ( const Name rName  )  [inline, private]

Constructs a LaserRangeFinder object with given ID

Definition at line 3934 of file Karto.h.

karto::LaserRangeFinder::LaserRangeFinder ( const LaserRangeFinder  )  [private]

Member Function Documentation

static LaserRangeFinder* karto::LaserRangeFinder::CreateLaserRangeFinder ( LaserRangeFinderType  type,
const Name rName 
) [inline, static]

Create a laser range finder of the given type and ID

Parameters:
type 
rName name of sensor - if no name is specified default name will be assigned
Returns:
laser range finder

Definition at line 3788 of file Karto.h.

kt_double karto::LaserRangeFinder::GetAngularResolution (  )  const [inline]

Gets this range finder sensor's angular resolution

Returns:
angular resolution

Definition at line 3682 of file Karto.h.

kt_double karto::LaserRangeFinder::GetMaximumAngle (  )  const [inline]

Gets this range finder sensor's maximum angle

Returns:
maximum angle

Definition at line 3662 of file Karto.h.

kt_double karto::LaserRangeFinder::GetMaximumRange (  )  const [inline]

Gets this range finder sensor's maximum range

Returns:
maximum range

Definition at line 3598 of file Karto.h.

kt_double karto::LaserRangeFinder::GetMinimumAngle (  )  const [inline]

Gets this range finder sensor's minimum angle

Returns:
minimum angle

Definition at line 3642 of file Karto.h.

kt_double karto::LaserRangeFinder::GetMinimumRange (  )  const [inline]

Gets this range finder sensor's minimum range

Returns:
minimum range

Definition at line 3578 of file Karto.h.

kt_int32u karto::LaserRangeFinder::GetNumberOfRangeReadings (  )  const [inline]

Gets the number of range readings each localized range scan must contain to be a valid scan.

Returns:
number of range readings

Definition at line 3755 of file Karto.h.

const PointVectorDouble karto::LaserRangeFinder::GetPointReadings ( LocalizedRangeScan pLocalizedRangeScan,
CoordinateConverter pCoordinateConverter,
kt_bool  ignoreThresholdPoints = true,
kt_bool  flipY = false 
) const

Get point readings (potentially scale readings if given coordinate converter is not null)

Parameters:
pCoordinateConverter 

Definition at line 142 of file Karto.cpp.

kt_double karto::LaserRangeFinder::GetRangeThreshold (  )  const [inline]

Gets the range threshold

Returns:
range threshold

Definition at line 3618 of file Karto.h.

kt_int32s karto::LaserRangeFinder::GetType (  )  [inline]

Definition at line 3746 of file Karto.h.

karto::LaserRangeFinder::KARTO_Object ( LaserRangeFinder   )  [inline]

Destructor

Definition at line 3563 of file Karto.h.

const LaserRangeFinder& karto::LaserRangeFinder::operator= ( const LaserRangeFinder  )  [private]
void karto::LaserRangeFinder::SetAngularResolution ( kt_double  angularResolution  )  [inline]

Sets this range finder sensor's angular resolution

Parameters:
angularResolution 

Definition at line 3691 of file Karto.h.

void karto::LaserRangeFinder::SetMaximumAngle ( kt_double  maximumAngle  )  [inline]

Sets this range finder sensor's maximum angle

Parameters:
maximumAngle 

Definition at line 3671 of file Karto.h.

void karto::LaserRangeFinder::SetMaximumRange ( kt_double  maximumRange  )  [inline]

Sets this range finder sensor's maximum range

Parameters:
maximumRange 

Definition at line 3607 of file Karto.h.

void karto::LaserRangeFinder::SetMinimumAngle ( kt_double  minimumAngle  )  [inline]

Sets this range finder sensor's minimum angle

Parameters:
minimumAngle 

Definition at line 3651 of file Karto.h.

void karto::LaserRangeFinder::SetMinimumRange ( kt_double  minimumRange  )  [inline]

Sets this range finder sensor's minimum range

Parameters:
minimumRange 

Definition at line 3587 of file Karto.h.

void karto::LaserRangeFinder::SetRangeThreshold ( kt_double  rangeThreshold  )  [inline]

Sets the range threshold

Parameters:
rangeThreshold 

Definition at line 3627 of file Karto.h.

void karto::LaserRangeFinder::Update (  )  [inline, private]

Set the number of range readings based on the minimum and maximum angles of the sensor and the angular resolution

Definition at line 3960 of file Karto.h.

kt_bool karto::LaserRangeFinder::Validate ( SensorData pSensorData  )  [virtual]

Validates sensor data

Parameters:
pSensorData sensor data
Returns:
true if valid

Implements karto::Sensor.

Definition at line 187 of file Karto.cpp.

virtual kt_bool karto::LaserRangeFinder::Validate (  )  [inline, virtual]

Validates sensor

Returns:
true if valid

Implements karto::Sensor.

Definition at line 3760 of file Karto.h.


Member Data Documentation

Definition at line 3983 of file Karto.h.

Definition at line 3974 of file Karto.h.

Definition at line 3972 of file Karto.h.

Definition at line 3977 of file Karto.h.

Definition at line 3971 of file Karto.h.

Definition at line 3976 of file Karto.h.

Definition at line 3979 of file Karto.h.

Definition at line 3981 of file Karto.h.


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


karto
Author(s): SRI International (package maintained by Brian Gerkey)
autogenerated on Fri Jan 11 10:07:05 2013