Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | Friends | 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_bool GetIs360Laser () 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 ()
 
 LaserRangeFinder ()
 
void SetAngularResolution (kt_double angularResolution)
 
void SetIs360Laser (bool is_360_laser)
 
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
 
 Sensor ()
 
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)
 
 Object (const Object &)
 
const Objectoperator= (const Object &)
 
template<typename T >
void SetParameter (const std::string &rName, T value)
 
virtual ~Object ()
 
- Public Member Functions inherited from karto::NonCopyable
 NonCopyable ()
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 
virtual ~NonCopyable ()
 

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 &)
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 
void Update ()
 

Private Attributes

kt_int32u m_NumberOfRangeReadings
 
Parameter< kt_double > * m_pAngularResolution
 
Parameter< kt_bool > * m_pIs360Laser
 
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
 

Friends

class boost::serialization::access
 

Additional Inherited Members

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

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

Constructor & Destructor Documentation

◆ LaserRangeFinder() [1/3]

karto::LaserRangeFinder::LaserRangeFinder ( )
inline

Definition at line 3925 of file Karto.h.

◆ ~LaserRangeFinder()

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

Destructor

Definition at line 3936 of file Karto.h.

◆ LaserRangeFinder() [2/3]

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

Constructs a LaserRangeFinder object with given ID

Definition at line 4334 of file Karto.h.

◆ LaserRangeFinder() [3/3]

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

Member Function Documentation

◆ CreateLaserRangeFinder()

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

◆ GetAngularResolution()

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

Gets this range finder sensor's angular resolution

Returns
angular resolution

Definition at line 4049 of file Karto.h.

◆ GetIs360Laser()

kt_bool karto::LaserRangeFinder::GetIs360Laser ( ) const
inline

Gets if this range finder sensor is 360° laser

Returns
is360Laser

Definition at line 4135 of file Karto.h.

◆ GetMaximumAngle()

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

Gets this range finder sensor's maximum angle

Returns
maximum angle

Definition at line 4029 of file Karto.h.

◆ GetMaximumRange()

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

Gets this range finder sensor's maximum range

Returns
maximum range

Definition at line 3965 of file Karto.h.

◆ GetMinimumAngle()

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

Gets this range finder sensor's minimum angle

Returns
minimum angle

Definition at line 4009 of file Karto.h.

◆ GetMinimumRange()

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

Gets this range finder sensor's minimum range

Returns
minimum range

Definition at line 3945 of file Karto.h.

◆ GetNumberOfRangeReadings()

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

◆ GetPointReadings()

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 164 of file Karto.cpp.

◆ GetRangeThreshold()

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

Gets the range threshold

Returns
range threshold

Definition at line 3985 of file Karto.h.

◆ GetType()

kt_int32s karto::LaserRangeFinder::GetType ( )
inline

Return Laser type

Definition at line 4116 of file Karto.h.

◆ operator=()

const LaserRangeFinder& karto::LaserRangeFinder::operator= ( const LaserRangeFinder )
private

◆ serialize()

template<class Archive >
void karto::LaserRangeFinder::serialize ( Archive &  ar,
const unsigned int  version 
)
inlineprivate

Definition at line 4403 of file Karto.h.

◆ SetAngularResolution()

void karto::LaserRangeFinder::SetAngularResolution ( kt_double  angularResolution)
inline

Sets this range finder sensor's angular resolution

Parameters
angularResolution

Definition at line 4058 of file Karto.h.

◆ SetIs360Laser()

void karto::LaserRangeFinder::SetIs360Laser ( bool  is_360_laser)
inline

Sets if this range finder sensor is 360° laser

Parameters
is360Laser

Definition at line 4144 of file Karto.h.

◆ SetMaximumAngle()

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

Sets this range finder sensor's maximum angle

Parameters
maximumAngle

Definition at line 4038 of file Karto.h.

◆ SetMaximumRange()

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

Sets this range finder sensor's maximum range

Parameters
maximumRange

Definition at line 3974 of file Karto.h.

◆ SetMinimumAngle()

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

Sets this range finder sensor's minimum angle

Parameters
minimumAngle

Definition at line 4018 of file Karto.h.

◆ SetMinimumRange()

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

Sets this range finder sensor's minimum range

Parameters
minimumRange

Definition at line 3954 of file Karto.h.

◆ SetRangeThreshold()

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

Sets the range threshold

Parameters
rangeThreshold

Definition at line 3994 of file Karto.h.

◆ Update()

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

◆ Validate() [1/2]

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

Validates sensor

Returns
true if valid

Implements karto::Sensor.

Definition at line 4152 of file Karto.h.

◆ Validate() [2/2]

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

Validates sensor data

Parameters
pSensorDatasensor data
Returns
true if valid

Implements karto::Sensor.

Definition at line 212 of file Karto.cpp.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Definition at line 4401 of file Karto.h.

Member Data Documentation

◆ m_NumberOfRangeReadings

kt_int32u karto::LaserRangeFinder::m_NumberOfRangeReadings
private

Definition at line 4398 of file Karto.h.

◆ m_pAngularResolution

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

Definition at line 4387 of file Karto.h.

◆ m_pIs360Laser

Parameter<kt_bool>* karto::LaserRangeFinder::m_pIs360Laser
private

Definition at line 4394 of file Karto.h.

◆ m_pMaximumAngle

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

Definition at line 4385 of file Karto.h.

◆ m_pMaximumRange

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

Definition at line 4390 of file Karto.h.

◆ m_pMinimumAngle

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

Definition at line 4384 of file Karto.h.

◆ m_pMinimumRange

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

Definition at line 4389 of file Karto.h.

◆ m_pRangeThreshold

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

Definition at line 4392 of file Karto.h.

◆ m_pType

ParameterEnum* karto::LaserRangeFinder::m_pType
private

Definition at line 4396 of file Karto.h.


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


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56