#include <SensorData.h>
Public Member Functions | |
const Pose2 & | GetBarycenterPose () const |
const BoundingBox2 & | GetBoundingBox () const |
LaserRangeFinder * | GetLaserRangeFinder () const |
kt_size_t | GetNumberOfRangeReadings () const |
const Vector2dList & | GetPointReadings (kt_bool wantFiltered=false) const |
const RangeReadingsList & | GetRangeReadings () const |
Pose2 | GetReferencePose (kt_bool useBarycenter) const |
Pose2 | GetSensorAt (const Pose2 &rPose) const |
Pose2 | GetSensorPose () const |
virtual void | SetCorrectedPose (const Pose2 &rCorrectedPose) |
void | SetSensorPose (const Pose2 &rSensorPose) |
Public Member Functions inherited from karto::LocalizedObject | |
LocalizedObject (const Identifier &rSensorIdentifier) | |
Public Member Functions inherited from karto::Object | |
Object () | |
Object (const Identifier &rIdentifier) | |
Public Member Functions inherited from karto::Referenced | |
Referenced () | |
Protected Member Functions | |
virtual void | ComputePointReadings ()=0 |
virtual const Vector2dList & | GetFilteredPointReadings () const |
virtual const Vector2dList & | GetUnfilteredPointReadings () const |
LocalizedLaserScan (const Identifier &rSensorIdentifier) | |
void | Update () |
virtual | ~LocalizedLaserScan () |
Protected Member Functions inherited from karto::LocalizedObject | |
const Pose2 & | GetCorrectedPose () const |
gps::PointGps | GetGpsEstimate () const |
gps::PointGps | GetGpsReading () const |
const Pose2 & | GetOdometricPose () const |
kt_bool | IsGpsEstimateValid () const |
kt_bool | IsGpsReadingValid () const |
void | SetGpsEstimate (const gps::PointGps &rGpsEstimate) |
void | SetGpsEstimationManager (AbstractGpsEstimationManager *pGpsEstimationManager) |
void | SetGpsReading (const gps::PointGps &rGpsReading) |
void | SetOdometricPose (const Pose2 &rOdometricPose) |
Protected Member Functions inherited from karto::SensorData | |
void | AddCustomItem (CustomItem *pCustomItem) |
const CustomItemList & | GetCustomItems () const |
const Identifier & | GetSensorIdentifier () const |
kt_int32s | GetStateId () const |
kt_int64s | GetTime () const |
kt_int32s | GetUniqueId () const |
kt_bool | HasCustomItem () |
SensorData (const Identifier &rSensorIdentifier) | |
void | SetSensorIdentifier (const Identifier &rSensorIdentifier) |
void | SetStateId (kt_int32s stateId) |
void | SetTime (kt_int64s time) |
void | SetUniqueId (kt_int32u uniqueId) |
Protected Member Functions inherited from karto::Object | |
const Identifier & | GetIdentifier () const |
AbstractParameter * | GetParameter (const String &rParameterName) const |
template<typename T > | |
Parameter< T > * | GetParameter (const String &rParameterName) const |
ParameterList | GetParameters () |
ParameterSet * | GetParameterSet () |
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 |
Protected Attributes | |
Vector2dList | m_FilteredPointReadings |
RangeReadingsList | m_RangeReadings |
Vector2dList | m_UnfilteredPointReadings |
Private Member Functions | |
KARTO_RTTI () | |
Private Attributes | |
Pose2 | m_BarycenterPose |
BoundingBox2 | m_BoundingBox |
kt_bool | m_IsDirty |
Identifier | m_SensorIdentifier |
Base class for localized laser scans
Definition at line 567 of file SensorData.h.
|
protected |
Localized laser scan from the given sensor
rSensorIdentifier | sensor identifier |
Definition at line 107 of file SensorData.cpp.
|
protectedvirtual |
Definition at line 113 of file SensorData.cpp.
|
protectedpure virtual |
Computes point readings in global coordinates
Implemented in karto::LocalizedRangeScan, and karto::LocalizedPointScan.
|
inline |
Gets barycenter of point readings
Definition at line 596 of file SensorData.h.
|
inline |
Gets the bounding box of this scan
Definition at line 666 of file SensorData.h.
|
inlineprotectedvirtual |
Gets filtered points readings
Definition at line 724 of file SensorData.h.
|
inline |
Gets the laser range finder sensor that generated this scan
Definition at line 576 of file SensorData.h.
|
inline |
Gets the number of range readings
Definition at line 697 of file SensorData.h.
const Vector2dList & karto::LocalizedLaserScan::GetPointReadings | ( | kt_bool | wantFiltered = false | ) | const |
Gets the point readings of this scan
wantFiltered | whether filtered points are to be included or not |
Definition at line 152 of file SensorData.cpp.
|
inline |
Gets the range readings of this scan
Definition at line 688 of file SensorData.h.
Gets barycenter if the given parameter is true, otherwise returns the scanner pose
useBarycenter | whether to use the barycenter as the reference pose |
Definition at line 612 of file SensorData.h.
Computes the position of the sensor if the robot were at the given pose
rPose | hypothesized pose |
Definition at line 657 of file SensorData.h.
|
inline |
|
inlineprotectedvirtual |
|
private |
|
inlinevirtual |
Moves the scan by moving the robot pose to the given location.
rCorrectedPose | new pose of the robot of this scan |
Reimplemented from karto::LocalizedObject.
Definition at line 585 of file SensorData.h.
|
inline |
Computes the robot pose from the given sensor pose
rSensorPose | new pose of the sensor |
Definition at line 636 of file SensorData.h.
|
protected |
Computes the point readings, bounding box, and barycenter of the scan
Definition at line 117 of file SensorData.cpp.
|
private |
Average of all the point readings
Definition at line 763 of file SensorData.h.
|
private |
Bounding box of localized range scan
Definition at line 768 of file SensorData.h.
|
protected |
List of filtered point readings
Definition at line 742 of file SensorData.h.
|
private |
Internal flag used to update point readings, barycenter and bounding box
Definition at line 773 of file SensorData.h.
|
protected |
List of unfiltered ranges
Definition at line 752 of file SensorData.h.
|
private |
Name of sensor that created this scan
Definition at line 758 of file SensorData.h.
|
protected |
List of unfiltered point readings
Definition at line 747 of file SensorData.h.