Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends | List of all members
karto::LocalizedRangeScan Class Reference

#include <Karto.h>

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

Public Member Functions

const Pose2GetBarycenterPose () const
 
const BoundingBox2GetBoundingBox () const
 
Pose2 GetCorrectedAt (const Pose2 &sPose) const
 Computes the pose of the robot if the sensor were at the given pose. More...
 
const Pose2GetCorrectedPose () const
 
const Pose2GetOdometricPose () const
 
const PointVectorDoubleGetPointReadings (kt_bool wantFiltered=false) const
 
Pose2 GetReferencePose (kt_bool useBarycenter) const
 
Pose2 GetSensorAt (const Pose2 &rPose) const
 
Pose2 GetSensorPose () const
 
 LocalizedRangeScan (const Name &rSensorName, const RangeReadingsVector &rReadings)
 
 LocalizedRangeScan ()
 
void SetBarycenterPose (Pose2 &bcenter)
 
void SetBoundingBox (BoundingBox2 &bbox)
 
void SetCorrectedPose (const Pose2 &rPose)
 
void SetCorrectedPoseAndUpdate (const Pose2 &rPose)
 
void SetIsDirty (kt_bool &rIsDirty)
 
void SetOdometricPose (const Pose2 &rPose)
 
void SetPointReadings (PointVectorDouble &points, kt_bool setFiltered=false)
 
void SetSensorPose (const Pose2 &rScanPose)
 
virtual ~LocalizedRangeScan ()
 
- Public Member Functions inherited from karto::LaserRangeScan
LaserRangeFinderGetLaserRangeFinder () const
 
kt_int32u GetNumberOfRangeReadings () const
 
kt_doubleGetRangeReadings () const
 
RangeReadingsVector GetRangeReadingsVector () const
 
 LaserRangeScan (const Name &rSensorName)
 
 LaserRangeScan ()
 
 LaserRangeScan (const Name &rSensorName, const RangeReadingsVector &rRangeReadings)
 
void SetRangeReadings (const RangeReadingsVector &rRangeReadings)
 
virtual ~LaserRangeScan ()
 
- Public Member Functions inherited from karto::SensorData
void AddCustomData (CustomData *pCustomData)
 
const CustomDataVectorGetCustomData () const
 
const NameGetSensorName () const
 
kt_int32s GetStateId () const
 
kt_double GetTime () const
 
kt_int32s GetUniqueId () const
 
 SensorData ()
 
void SetStateId (kt_int32s stateId)
 
void SetTime (kt_double time)
 
void SetUniqueId (kt_int32u uniqueId)
 
virtual ~SensorData ()
 
- 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 ()
 

Protected Attributes

Pose2 m_BarycenterPose
 
BoundingBox2 m_BoundingBox
 
kt_bool m_IsDirty
 
PointVectorDouble m_PointReadings
 
PointVectorDouble m_UnfilteredPointReadings
 

Private Member Functions

 LocalizedRangeScan (const LocalizedRangeScan &)
 
const LocalizedRangeScanoperator= (const LocalizedRangeScan &)
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 
virtual void Update ()
 

Private Attributes

Pose2 m_CorrectedPose
 
boost::shared_mutex m_Lock
 
Pose2 m_OdometricPose
 

Friends

class boost::serialization::access
 

Additional Inherited Members

- Protected Member Functions inherited from karto::SensorData
 SensorData (const Name &rSensorName)
 

Detailed Description

The LocalizedRangeScan contains range data from a single sweep of a laser range finder sensor in a two-dimensional space and position information. The odometer position is the position reported by the robot when the range data was recorded. The corrected position is the position calculated by the mapper (or localizer)

Definition at line 5503 of file Karto.h.

Constructor & Destructor Documentation

◆ LocalizedRangeScan() [1/3]

karto::LocalizedRangeScan::LocalizedRangeScan ( const Name rSensorName,
const RangeReadingsVector rReadings 
)
inline

Constructs a range scan from the given range finder with the given readings

Definition at line 5514 of file Karto.h.

◆ LocalizedRangeScan() [2/3]

karto::LocalizedRangeScan::LocalizedRangeScan ( )
inline

Definition at line 5520 of file Karto.h.

◆ ~LocalizedRangeScan()

virtual karto::LocalizedRangeScan::~LocalizedRangeScan ( )
inlinevirtual

Destructor

Definition at line 5526 of file Karto.h.

◆ LocalizedRangeScan() [3/3]

karto::LocalizedRangeScan::LocalizedRangeScan ( const LocalizedRangeScan )
private

Member Function Documentation

◆ GetBarycenterPose()

const Pose2& karto::LocalizedRangeScan::GetBarycenterPose ( ) const
inline

Gets barycenter of point readings

Definition at line 5590 of file Karto.h.

◆ GetBoundingBox()

const BoundingBox2& karto::LocalizedRangeScan::GetBoundingBox ( ) const
inline

Gets the bounding box of this scan

Returns
bounding box of this scan

Definition at line 5686 of file Karto.h.

◆ GetCorrectedAt()

Pose2 karto::LocalizedRangeScan::GetCorrectedAt ( const Pose2 sPose) const
inline

Computes the pose of the robot if the sensor were at the given pose.

Parameters
sPosesensor pose
Returns
robot pose

Definition at line 5668 of file Karto.h.

◆ GetCorrectedPose()

const Pose2& karto::LocalizedRangeScan::GetCorrectedPose ( ) const
inline

Gets the (possibly corrected) robot pose at which this scan was taken. The corrected robot pose of the scan is usually set by an external module such as a localization or mapping module when it is determined that the original pose was incorrect. The external module will set the correct pose based on additional sensor data and any context information it has. If the pose has not been corrected, a call to this method returns the same pose as GetOdometricPose().

Returns
corrected pose

Definition at line 5560 of file Karto.h.

◆ GetOdometricPose()

const Pose2& karto::LocalizedRangeScan::GetOdometricPose ( ) const
inline

Gets the odometric pose of this scan

Returns
odometric pose of this scan

Definition at line 5538 of file Karto.h.

◆ GetPointReadings()

const PointVectorDouble& karto::LocalizedRangeScan::GetPointReadings ( kt_bool  wantFiltered = false) const
inline

Get point readings in local coordinates

Definition at line 5708 of file Karto.h.

◆ GetReferencePose()

Pose2 karto::LocalizedRangeScan::GetReferencePose ( kt_bool  useBarycenter) const
inline

Gets barycenter if the given parameter is true, otherwise returns the scanner pose

Parameters
useBarycenter
Returns
barycenter if parameter is true, otherwise scanner pose

Definition at line 5614 of file Karto.h.

◆ GetSensorAt()

Pose2 karto::LocalizedRangeScan::GetSensorAt ( const Pose2 rPose) const
inline

Computes the position of the sensor if the robot were at the given pose

Parameters
rPose
Returns
sensor pose

Definition at line 5658 of file Karto.h.

◆ GetSensorPose()

Pose2 karto::LocalizedRangeScan::GetSensorPose ( ) const
inline

Computes the position of the sensor

Returns
scan pose

Definition at line 5632 of file Karto.h.

◆ operator=()

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

◆ serialize()

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

Definition at line 5819 of file Karto.h.

◆ SetBarycenterPose()

void karto::LocalizedRangeScan::SetBarycenterPose ( Pose2 bcenter)
inline

Definition at line 5604 of file Karto.h.

◆ SetBoundingBox()

void karto::LocalizedRangeScan::SetBoundingBox ( BoundingBox2 bbox)
inline

Definition at line 5700 of file Karto.h.

◆ SetCorrectedPose()

void karto::LocalizedRangeScan::SetCorrectedPose ( const Pose2 rPose)
inline

Moves the scan by moving the robot pose to the given location.

Parameters
rPosenew pose of the robot of this scan

Definition at line 5569 of file Karto.h.

◆ SetCorrectedPoseAndUpdate()

void karto::LocalizedRangeScan::SetCorrectedPoseAndUpdate ( const Pose2 rPose)
inline

Moves the scan by moving the robot pose to the given location and update point readings.

Parameters
rPosenew pose of the robot of this scan

Definition at line 5580 of file Karto.h.

◆ SetIsDirty()

void karto::LocalizedRangeScan::SetIsDirty ( kt_bool rIsDirty)
inline

Definition at line 5637 of file Karto.h.

◆ SetOdometricPose()

void karto::LocalizedRangeScan::SetOdometricPose ( const Pose2 rPose)
inline

Sets the odometric pose of this scan

Parameters
rPose

Definition at line 5547 of file Karto.h.

◆ SetPointReadings()

void karto::LocalizedRangeScan::SetPointReadings ( PointVectorDouble points,
kt_bool  setFiltered = false 
)
inline

Definition at line 5729 of file Karto.h.

◆ SetSensorPose()

void karto::LocalizedRangeScan::SetSensorPose ( const Pose2 rScanPose)
inline

Computes the robot pose given the corrected scan pose

Parameters
rScanPosepose of the sensor

Definition at line 5646 of file Karto.h.

◆ Update()

virtual void karto::LocalizedRangeScan::Update ( )
inlineprivatevirtual

Compute point readings based on range readings Only range readings within [minimum range; range threshold] are returned

Reimplemented in karto::LocalizedRangeScanWithPoints.

Definition at line 5746 of file Karto.h.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Serialization: class LocalizedRangeScan

Definition at line 5817 of file Karto.h.

Member Data Documentation

◆ m_BarycenterPose

Pose2 karto::LocalizedRangeScan::m_BarycenterPose
protected

Average of all the point readings

Definition at line 5851 of file Karto.h.

◆ m_BoundingBox

BoundingBox2 karto::LocalizedRangeScan::m_BoundingBox
protected

Bounding box of localized range scan

Definition at line 5866 of file Karto.h.

◆ m_CorrectedPose

Pose2 karto::LocalizedRangeScan::m_CorrectedPose
private

Corrected pose of robot calculated by mapper (or localizer)

Definition at line 5845 of file Karto.h.

◆ m_IsDirty

kt_bool karto::LocalizedRangeScan::m_IsDirty
protected

Internal flag used to update point readings, barycenter and bounding box

Definition at line 5871 of file Karto.h.

◆ m_Lock

boost::shared_mutex karto::LocalizedRangeScan::m_Lock
mutableprivate

Definition at line 5531 of file Karto.h.

◆ m_OdometricPose

Pose2 karto::LocalizedRangeScan::m_OdometricPose
private

Odometric pose of robot

Definition at line 5840 of file Karto.h.

◆ m_PointReadings

PointVectorDouble karto::LocalizedRangeScan::m_PointReadings
protected

Vector of point readings

Definition at line 5856 of file Karto.h.

◆ m_UnfilteredPointReadings

PointVectorDouble karto::LocalizedRangeScan::m_UnfilteredPointReadings
protected

Vector of unfiltered point readings

Definition at line 5861 of file Karto.h.


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


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:49