Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes
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 ()
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 ()
virtual kt_bool Validate (SensorData *pSensorData)
virtual ~LaserRangeFinder ()

Static Public Member Functions

static LaserRangeFinderCreateLaserRangeFinder (LaserRangeFinderType type, const Name &rName)

Private Member Functions

 LaserRangeFinder (const Name &rName)
 LaserRangeFinder (const LaserRangeFinder &)
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 3710 of file Karto.h.


Constructor & Destructor Documentation

virtual karto::LaserRangeFinder::~LaserRangeFinder ( ) [inline, virtual]

Destructor

Definition at line 3721 of file Karto.h.

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

Constructs a LaserRangeFinder object with given ID

Definition at line 4097 of file Karto.h.


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
rNamename of sensor - if no name is specified default name will be assigned
Returns:
laser range finder

Definition at line 3950 of file Karto.h.

Gets this range finder sensor's angular resolution

Returns:
angular resolution

Definition at line 3834 of file Karto.h.

Gets this range finder sensor's maximum angle

Returns:
maximum angle

Definition at line 3814 of file Karto.h.

Gets this range finder sensor's maximum range

Returns:
maximum range

Definition at line 3750 of file Karto.h.

Gets this range finder sensor's minimum angle

Returns:
minimum angle

Definition at line 3794 of file Karto.h.

Gets this range finder sensor's minimum range

Returns:
minimum range

Definition at line 3730 of file Karto.h.

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 3910 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:
pLocalizedRangeScan
pCoordinateConverter
ignoreThresholdPoints
flipY

Definition at line 142 of file Karto.cpp.

Gets the range threshold

Returns:
range threshold

Definition at line 3770 of file Karto.h.

Return Laser type

Definition at line 3901 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 3843 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 3823 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 3759 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 3803 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 3739 of file Karto.h.

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

Sets the range threshold

Parameters:
rangeThreshold

Definition at line 3779 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 4126 of file Karto.h.

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

Validates sensor

Returns:
true if valid

Implements karto::Sensor.

Definition at line 3915 of file Karto.h.

Validates sensor data

Parameters:
pSensorDatasensor data
Returns:
true if valid

Implements karto::Sensor.

Definition at line 190 of file Karto.cpp.


Member Data Documentation

Definition at line 4151 of file Karto.h.

Definition at line 4142 of file Karto.h.

Definition at line 4140 of file Karto.h.

Definition at line 4145 of file Karto.h.

Definition at line 4139 of file Karto.h.

Definition at line 4144 of file Karto.h.

Definition at line 4147 of file Karto.h.

Definition at line 4149 of file Karto.h.


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


open_karto
Author(s):
autogenerated on Thu Aug 27 2015 14:14:06