Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
karto::LaserRangeFinder Class Reference

#include <Karto.h>

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

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 ()
 
- Public Member Functions inherited from karto::Sensor
const Pose2GetOffsetPose () const
 
void SetOffsetPose (const Pose2 &rPose)
 
virtual ~Sensor ()
 
- Public Member Functions inherited from karto::Object
virtual const char * GetClassName () const =0
 
const NameGetName () const
 
virtual kt_objecttype GetObjectType () const =0
 
AbstractParameterGetParameter (const std::string &rName) const
 
virtual ParameterManagerGetParameterManager ()
 
const ParameterVectorGetParameters () const
 
 Object ()
 
 Object (const Name &rName)
 
template<typename T >
void SetParameter (const std::string &rName, T value)
 
virtual ~Object ()
 

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
 

Additional Inherited Members

- Protected Member Functions inherited from karto::Sensor
 Sensor (const Name &rName)
 
- Protected Member Functions inherited from karto::NonCopyable
 NonCopyable ()
 
virtual ~NonCopyable ()
 

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 3721 of file Karto.h.

Constructor & Destructor Documentation

virtual karto::LaserRangeFinder::~LaserRangeFinder ( )
inlinevirtual

Destructor

Definition at line 3732 of file Karto.h.

karto::LaserRangeFinder::LaserRangeFinder ( const Name rName)
inlineprivate

Constructs a LaserRangeFinder object with given ID

Definition at line 4108 of file Karto.h.

karto::LaserRangeFinder::LaserRangeFinder ( const LaserRangeFinder )
private

Member Function Documentation

static LaserRangeFinder* karto::LaserRangeFinder::CreateLaserRangeFinder ( LaserRangeFinderType  type,
const Name rName 
)
inlinestatic

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 3961 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 3845 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 3825 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 3761 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 3805 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 3741 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 3921 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.

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

Gets the range threshold

Returns
range threshold

Definition at line 3781 of file Karto.h.

kt_int32s karto::LaserRangeFinder::GetType ( )
inline

Return Laser type

Definition at line 3912 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 3854 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 3834 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 3770 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 3814 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 3750 of file Karto.h.

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

Sets the range threshold

Parameters
rangeThreshold

Definition at line 3790 of file Karto.h.

void karto::LaserRangeFinder::Update ( )
inlineprivate

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

Definition at line 4137 of file Karto.h.

virtual kt_bool karto::LaserRangeFinder::Validate ( )
inlinevirtual

Validates sensor

Returns
true if valid

Implements karto::Sensor.

Definition at line 3926 of file Karto.h.

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

Validates sensor data

Parameters
pSensorDatasensor data
Returns
true if valid

Implements karto::Sensor.

Definition at line 190 of file Karto.cpp.

Member Data Documentation

kt_int32u karto::LaserRangeFinder::m_NumberOfRangeReadings
private

Definition at line 4162 of file Karto.h.

Parameter<kt_double>* karto::LaserRangeFinder::m_pAngularResolution
private

Definition at line 4153 of file Karto.h.

Parameter<kt_double>* karto::LaserRangeFinder::m_pMaximumAngle
private

Definition at line 4151 of file Karto.h.

Parameter<kt_double>* karto::LaserRangeFinder::m_pMaximumRange
private

Definition at line 4156 of file Karto.h.

Parameter<kt_double>* karto::LaserRangeFinder::m_pMinimumAngle
private

Definition at line 4150 of file Karto.h.

Parameter<kt_double>* karto::LaserRangeFinder::m_pMinimumRange
private

Definition at line 4155 of file Karto.h.

Parameter<kt_double>* karto::LaserRangeFinder::m_pRangeThreshold
private

Definition at line 4158 of file Karto.h.

ParameterEnum* karto::LaserRangeFinder::m_pType
private

Definition at line 4160 of file Karto.h.


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


open_karto
Author(s):
autogenerated on Mon Jun 10 2019 14:02:19