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

#include <Sensor.h>

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

Static Public Member Functions

static LaserRangeFinderCreateLaserRangeFinder (LaserRangeFinderType type, const Identifier &rName)
 

Protected 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 Vector2dList GetPointReadings (LocalizedLaserScan *pLocalizedLaserScan, CoordinateConverter *pCoordinateConverter, kt_bool ignoreThresholdPoints=true, kt_bool flipY=false) const
 
kt_double GetRangeThreshold () const
 
kt_int64s 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 void Validate ()
 
virtual void Validate (SensorData *pSensorData)
 
- Protected Member Functions inherited from karto::Sensor
const Pose2GetOffsetPose () const
 
 Sensor (const Identifier &rName)
 
void SetOffsetPose (const Pose2 &rPose)
 
- Protected Member Functions inherited from karto::Object
const IdentifierGetIdentifier () const
 
AbstractParameterGetParameter (const String &rParameterName) const
 
template<typename T >
Parameter< T > * GetParameter (const String &rParameterName) const
 
ParameterList GetParameters ()
 
ParameterSetGetParameterSet ()
 
template<typename T >
void SetParameters (const karto::String &rParameterName, const T &rValue)
 
- Protected Member Functions inherited from karto::Referenced
kt_int32s GetReferenceCount ()
 
kt_int32s Reference () const
 
kt_int32s Unreference () const
 
kt_int32s UnreferenceNoDelete () const
 

Private Member Functions

 KARTO_RTTI ()
 
 LaserRangeFinder (const Identifier &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

- Public Member Functions inherited from karto::Object
 Object ()
 
 Object (const Identifier &rIdentifier)
 
- Public Member Functions inherited from karto::Referenced
 Referenced ()
 

Detailed Description

The LaserRangeFinder defines a laser sensor that provides the pose offset position of a localized laser 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. It 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 following example code creates a LaserRangeFinder with default values for a Sick LMS100 laser

The following laser types are supported in CreateLaserRangeFinder

LaserRangeFinder_Sick_LMS100 LaserRangeFinder_Sick_LMS200 LaserRangeFinder_Sick_LMS291 LaserRangeFinder_Hokuyo_UTM_30LX LaserRangeFinder_Hokuyo_URG_04LX

Definition at line 247 of file Sensor.h.

Constructor & Destructor Documentation

karto::LaserRangeFinder::LaserRangeFinder ( const Identifier rName)
private

Laser range finder with given name

Parameters
rNamename

Definition at line 66 of file Sensor.cpp.

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

Member Function Documentation

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

Creates a laser range finder of the given type and name

Parameters
typelaser type
rNamename of sensor
Returns
laser range finder

Definition at line 229 of file Sensor.cpp.

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

Gets this range finder sensor's angular resolution

Returns
angular resolution

Definition at line 359 of file Sensor.h.

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

Gets this range finder sensor's maximum angle

Returns
maximum angle

Definition at line 339 of file Sensor.h.

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

Gets this range finder sensor's maximum range

Returns
maximum range

Definition at line 284 of file Sensor.h.

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

Gets this range finder sensor's minimum angle

Returns
minimum angle

Definition at line 319 of file Sensor.h.

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

public: /** Gets this range finder sensor's minimum range

Returns
minimum range

Definition at line 264 of file Sensor.h.

kt_int32u karto::LaserRangeFinder::GetNumberOfRangeReadings ( ) const
inlineprotected

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 383 of file Sensor.h.

const Vector2dList karto::LaserRangeFinder::GetPointReadings ( LocalizedLaserScan pLocalizedLaserScan,
CoordinateConverter pCoordinateConverter,
kt_bool  ignoreThresholdPoints = true,
kt_bool  flipY = false 
) const
protected

Gets point readings (potentially scaling readings if given coordinate converter is not null)

Parameters
pLocalizedLaserScanscan
pCoordinateConvertercoordinate converter
ignoreThresholdPointswhether to ignore points that exceed the range threshold
flipYwhether to flip the y-coordinate (useful for drawing applications with inverted y-coordinates)
Returns
list of points from the given scan

Definition at line 93 of file Sensor.cpp.

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

Gets the range threshold

Returns
range threshold

Definition at line 304 of file Sensor.h.

kt_int64s karto::LaserRangeFinder::GetType ( )
inlineprotected

Gets this range finder sensor's laser type

Returns
laser type of this range finder

Definition at line 374 of file Sensor.h.

karto::LaserRangeFinder::KARTO_RTTI ( )
private
const LaserRangeFinder& karto::LaserRangeFinder::operator= ( const LaserRangeFinder )
private
void karto::LaserRangeFinder::SetAngularResolution ( kt_double  angularResolution)
protected

Sets this range finder sensor's angular resolution

Parameters
angularResolutionnew angular resolution

Definition at line 138 of file Sensor.cpp.

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

Sets this range finder sensor's maximum angle

Parameters
maximumAnglenew maximum angle

Definition at line 348 of file Sensor.h.

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

Sets this range finder sensor's maximum range

Parameters
maximumRangenew maximum range

Definition at line 293 of file Sensor.h.

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

Sets this range finder sensor's minimum angle

Parameters
minimumAnglenew minimum angle

Definition at line 328 of file Sensor.h.

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

Sets this range finder sensor's minimum range

Parameters
minimumRangenew minimum range

Definition at line 273 of file Sensor.h.

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

Sets the range threshold

Parameters
rangeThresholdnew range threshold

Definition at line 127 of file Sensor.cpp.

void karto::LaserRangeFinder::Update ( )
inlineprivate

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

Definition at line 428 of file Sensor.h.

void karto::LaserRangeFinder::Validate ( )
protectedvirtual

Validates this sensor

Implements karto::Sensor.

Definition at line 192 of file Sensor.cpp.

void karto::LaserRangeFinder::Validate ( SensorData pSensorData)
protectedvirtual

Validates sensor data

Parameters
pSensorDatasensor data

Implements karto::Sensor.

Definition at line 212 of file Sensor.cpp.

Member Data Documentation

kt_int32u karto::LaserRangeFinder::m_NumberOfRangeReadings
private

Definition at line 451 of file Sensor.h.

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

Definition at line 442 of file Sensor.h.

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

Definition at line 440 of file Sensor.h.

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

Definition at line 445 of file Sensor.h.

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

Definition at line 439 of file Sensor.h.

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

Definition at line 444 of file Sensor.h.

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

Definition at line 447 of file Sensor.h.

ParameterEnum* karto::LaserRangeFinder::m_pType
private

Definition at line 449 of file Sensor.h.


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


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Tue Nov 7 2017 06:02:36