Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes
mrpt::obs::CObservation2DRangeScan Class Reference

Detailed Description

A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser scanner).

The data structures are generic enough to hold a wide variety of 2D scanners and "3D" planar rotating 2D lasers.

These are the most important data fields:

See also
CObservation, CPointsMap, T2DScanProperties

Definition at line 56 of file CObservation2DRangeScan.h.

#include <mrpt/obs/CObservation2DRangeScan.h>

Inheritance diagram for mrpt::obs::CObservation2DRangeScan:
Inheritance graph

Public Types

using TListExclusionAreas = std::vector< mrpt::math::CPolygon >
 Used in filterByExclusionAreas. More...
 
using TListExclusionAreasWithRanges = std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > >>
 Used in filterByExclusionAreas. More...
 

Public Member Functions

voidoperator new (size_t size)
 
voidoperator new[] (size_t size)
 
void operator delete (void *ptr) noexcept
 
void operator delete[] (void *ptr) noexcept
 
void operator delete (void *memory, void *ptr) noexcept
 
voidoperator new (size_t size, const std::nothrow_t &) noexcept
 
void operator delete (void *ptr, const std::nothrow_t &) noexcept
 
 CObservation2DRangeScan ()=default
 Default constructor. More...
 
 CObservation2DRangeScan (const CObservation2DRangeScan &o)
 copy ctor More...
 
void loadFromVectors (size_t nRays, const float *scanRanges, const char *scanValidity)
 
bool isPlanarScan (const double tolerance=0) const
 Return true if the laser scanner is "horizontal", so it has an absolute value of "pitch" and "roll" less or equal to the given tolerance (in rads, default=0) (with the normal vector either upwards or downwards). More...
 
bool hasIntensity () const
 Return true if scan has intensity. More...
 
void setScanHasIntensity (bool setHasIntensityFlag)
 Marks this scan as having or not intensity data. More...
 
void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const override
 A general method to retrieve the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::poses::CPose3D &newSensorPose) override
 A general method to change the sensor pose on the robot. More...
 
void getDescriptionAsText (std::ostream &o) const override
 Build a detailed, multi-line textual description of the observation contents and dump it to the output stream. More...
 
void truncateByDistanceAndAngle (float min_distance, float max_angle, float min_height=0, float max_height=0, float h=0)
 A general method to truncate the scan by defining a minimum valid distance and a maximum valid angle as well as minimun and maximum heights (NOTE: the laser z-coordinate must be provided). More...
 
void filterByExclusionAreas (const TListExclusionAreas &areas)
 Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose"). More...
 
void filterByExclusionAreas (const TListExclusionAreasWithRanges &areas)
 Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose"), AND such as the Z coordinate of the point falls in the range [min,max] associated to each exclusion polygon. More...
 
void filterByExclusionAngles (const std::vector< std::pair< double, double >> &angles)
 Mark as invalid the ranges in any of a given set of "forbiden angle ranges", given as pairs<min_angle,max_angle>. More...
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=nullptr) const
 This method is equivalent to: More...
 
void getSensorPose (mrpt::math::TPose3D &out_sensorPose) const
 A general method to retrieve the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::math::TPose3D &newSensorPose)
 A general method to change the sensor pose on the robot. More...
 
virtual mxArraywriteToMatlab () const
 Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More...
 

Static Public Member Functions

static voidoperator new (size_t size, void *ptr)
 

Protected Member Functions

void swap (CObservation &o)
 Swap with another observation, ONLY the data defined here in the base class CObservation. More...
 
CSerializable virtual methods
uint8_t serializeGetVersion () const override
 Must return the current versioning number of the object. More...
 
void serializeTo (mrpt::serialization::CArchive &out) const override
 Pure virtual method for writing (serializing) to an abstract archive. More...
 
void serializeFrom (mrpt::serialization::CArchive &in, uint8_t serial_version) override
 Pure virtual method for reading (deserializing) from an abstract archive. More...
 

Private Attributes

mrpt::aligned_std_vector< float > m_scan
 The range values of the scan, in meters. More...
 
mrpt::aligned_std_vector< int32_tm_intensity
 The intensity values of the scan. More...
 
mrpt::aligned_std_vector< char > m_validRange
 It's false (=0) on no reflected rays, referenced to elements in scan. More...
 
bool m_has_intensity {false}
 Whether the intensity values are present or not. More...
 

Data common to any observation

mrpt::system::TTimeStamp timestamp {mrpt::system::now()}
 The associated UTC time-stamp. More...
 
std::string sensorLabel
 An arbitrary label that can be used to identify the sensor. More...
 
mrpt::system::TTimeStamp getTimeStamp () const
 Returns CObservation::timestamp for all kind of observations. More...
 
virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp () const
 By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp. More...
 

RTTI stuff


using Ptr = std::shared_ptr< CObservation2DRangeScan >
 
using ConstPtr = std::shared_ptr< const CObservation2DRangeScan >
 
using UniquePtr = std::unique_ptr< CObservation2DRangeScan >
 
using ConstUniquePtr = std::unique_ptr< const CObservation2DRangeScan >
 
static mrpt::rtti::CLASSINIT _init_CObservation2DRangeScan
 
static const mrpt::rtti::TRuntimeClassId runtimeClassId
 
static constexpr const char * className = "CObservation2DRangeScan"
 
static const mrpt::rtti::TRuntimeClassId_GetBaseClass ()
 
static constexpr auto getClassName ()
 
static const mrpt::rtti::TRuntimeClassIdGetRuntimeClassIdStatic ()
 
static mrpt::rtti::CObjectCreateObject ()
 
template<typename... Args>
static Ptr Create (Args &&... args)
 
template<typename... Args>
static UniquePtr CreateUnique (Args &&... args)
 
virtual const mrpt::rtti::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::rtti::CObjectclone () const override
 Returns a deep copy (clone) of the object, indepently of its class. More...
 

Scan data

mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< float > > scan {m_scan}
 The range values of the scan, in meters. More...
 
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< int32_t > > intensity {m_intensity}
 The intensity values of the scan. More...
 
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< char > > validRange {m_validRange}
 It's false (=0) on no reflected rays, referenced to elements in scan. More...
 
float aperture {M_PIf}
 The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees). More...
 
bool rightToLeft {true}
 The scanning direction: true=counterclockwise; false=clockwise. More...
 
float maxRange {80.0f}
 The maximum range allowed by the device, in meters (e.g. More...
 
mrpt::poses::CPose3D sensorPose
 The 6D pose of the sensor on the robot at the moment of starting the scan. More...
 
float stdError {0.01f}
 The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid. More...
 
float beamAperture {0}
 The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid. More...
 
double deltaPitch {0}
 If the laser gathers data by sweeping in the pitch/elevation angle, this holds the increment in "pitch" (=-"elevation") between the beginning and the end of the scan (the sensorPose member stands for the pose at the beginning of the scan). More...
 
void resizeScan (const size_t len)
 Resizes all data vectors to allocate a given number of scan rays. More...
 
void resizeScanAndAssign (const size_t len, const float rangeVal, const bool rangeValidity, const int32_t rangeIntensity=0)
 Resizes all data vectors to allocate a given number of scan rays and assign default values. More...
 
size_t getScanSize () const
 Get number of scan rays. More...
 
float getScanRange (const size_t i) const
 
void setScanRange (const size_t i, const float val)
 
int32_t getScanIntensity (const size_t i) const
 
void setScanIntensity (const size_t i, const int val)
 
bool getScanRangeValidity (const size_t i) const
 
void setScanRangeValidity (const size_t i, const bool val)
 
void getScanProperties (T2DScanProperties &p) const
 Fill out a T2DScanProperties structure with the parameters of this scan. More...
 

Cached points map


mrpt::maps::CMetricMap::Ptr m_cachedMap
 A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap(). More...
 
template<class POINTSMAP >
const POINTSMAP * getAuxPointsMap () const
 Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or nullptr otherwise. More...
 
template<class POINTSMAP >
const POINTSMAP * buildAuxPointsMap (const void *options=nullptr) const
 Returns a cached points map representing this laser scan, building it upon the first call. More...
 
void internal_buildAuxPointsMap (const void *options=nullptr) const
 Internal method, used from buildAuxPointsMap() More...
 

Member Typedef Documentation

◆ ConstPtr

Definition at line 58 of file CObservation2DRangeScan.h.

◆ ConstUniquePtr

Definition at line 58 of file CObservation2DRangeScan.h.

◆ Ptr

A type for the associated smart pointer

Definition at line 58 of file CObservation2DRangeScan.h.

◆ TListExclusionAreas

Used in filterByExclusionAreas.

Definition at line 77 of file CObservation2DRangeScan.h.

◆ TListExclusionAreasWithRanges

using mrpt::obs::CObservation2DRangeScan::TListExclusionAreasWithRanges = std::vector<std::pair<mrpt::math::CPolygon, std::pair<double, double> >>

Used in filterByExclusionAreas.

Definition at line 80 of file CObservation2DRangeScan.h.

◆ UniquePtr

Definition at line 58 of file CObservation2DRangeScan.h.

Constructor & Destructor Documentation

◆ CObservation2DRangeScan() [1/2]

mrpt::obs::CObservation2DRangeScan::CObservation2DRangeScan ( )
default

Default constructor.

◆ CObservation2DRangeScan() [2/2]

CObservation2DRangeScan::CObservation2DRangeScan ( const CObservation2DRangeScan o)

copy ctor

Definition at line 29 of file CObservation2DRangeScan.cpp.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::rtti::TRuntimeClassId* mrpt::obs::CObservation2DRangeScan::_GetBaseClass ( )
staticprotected

◆ buildAuxPointsMap()

template<class POINTSMAP >
const POINTSMAP* mrpt::obs::CObservation2DRangeScan::buildAuxPointsMap ( const void options = nullptr) const
inline

◆ clone()

virtual mrpt::rtti::CObject* mrpt::obs::CObservation2DRangeScan::clone ( ) const
overridevirtual

Returns a deep copy (clone) of the object, indepently of its class.

Implements mrpt::rtti::CObject.

◆ Create()

template<typename... Args>
static Ptr mrpt::obs::CObservation2DRangeScan::Create ( Args &&...  args)
inlinestatic

Definition at line 58 of file CObservation2DRangeScan.h.

◆ CreateObject()

static mrpt::rtti::CObject* mrpt::obs::CObservation2DRangeScan::CreateObject ( )
static

◆ CreateUnique()

template<typename... Args>
static UniquePtr mrpt::obs::CObservation2DRangeScan::CreateUnique ( Args &&...  args)
inlinestatic

Definition at line 58 of file CObservation2DRangeScan.h.

◆ duplicateGetSmartPtr()

mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr ( ) const
inlineinherited

Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).

Definition at line 169 of file CObject.h.

References mrpt::rtti::CObject::clone().

Referenced by mrpt::obs::CRawlog::addActions(), and mrpt::obs::CRawlog::addObservations().

◆ filterByExclusionAngles()

void CObservation2DRangeScan::filterByExclusionAngles ( const std::vector< std::pair< double, double >> &  angles)

Mark as invalid the ranges in any of a given set of "forbiden angle ranges", given as pairs<min_angle,max_angle>.

See also
C2DRangeFinderAbstract::loadExclusionAreas

Definition at line 351 of file CObservation2DRangeScan.cpp.

References ASSERT_, MRPT_END, MRPT_START, and mrpt::math::wrapTo2Pi().

Referenced by mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAngles().

◆ filterByExclusionAreas() [1/2]

void CObservation2DRangeScan::filterByExclusionAreas ( const TListExclusionAreas areas)

Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose").

See also
C2DRangeFinderAbstract::loadExclusionAreas

Definition at line 330 of file CObservation2DRangeScan.cpp.

Referenced by mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAreas().

◆ filterByExclusionAreas() [2/2]

void CObservation2DRangeScan::filterByExclusionAreas ( const TListExclusionAreasWithRanges areas)

Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose"), AND such as the Z coordinate of the point falls in the range [min,max] associated to each exclusion polygon.

See also
C2DRangeFinderAbstract::loadExclusionAreas

Definition at line 268 of file CObservation2DRangeScan.cpp.

References ASSERT_, MRPT_END, and MRPT_START.

◆ getAuxPointsMap()

template<class POINTSMAP >
const POINTSMAP* mrpt::obs::CObservation2DRangeScan::getAuxPointsMap ( ) const
inline

Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or nullptr otherwise.

Usage:

obs->getAuxPointsMap<mrpt::maps::CPointsMap>();
See also
buildAuxPointsMap

Definition at line 177 of file CObservation2DRangeScan.h.

References m_cachedMap.

◆ getClassName()

static constexpr auto mrpt::obs::CObservation2DRangeScan::getClassName ( )
inlinestaticconstexpr

Definition at line 58 of file CObservation2DRangeScan.h.

◆ getDescriptionAsText()

void CObservation2DRangeScan::getDescriptionAsText ( std::ostream &  o) const
overridevirtual

Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.

Note
If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.
This is the text that appears in RawLogViewer when selecting an object in the dataset

Reimplemented from mrpt::obs::CObservation.

Definition at line 460 of file CObservation2DRangeScan.cpp.

References RAD2DEG.

◆ getOriginalReceivedTimeStamp()

virtual mrpt::system::TTimeStamp mrpt::obs::CObservation::getOriginalReceivedTimeStamp ( ) const
inlinevirtualinherited

By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp.

See also
getTimeStamp()

Reimplemented in mrpt::obs::CObservationGPS, and mrpt::obs::CObservationVelodyneScan.

Definition at line 71 of file CObservation.h.

References mrpt::obs::CObservation::timestamp.

◆ GetRuntimeClass()

virtual const mrpt::rtti::TRuntimeClassId* mrpt::obs::CObservation2DRangeScan::GetRuntimeClass ( ) const
overridevirtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::obs::CObservation.

◆ GetRuntimeClassIdStatic()

static const mrpt::rtti::TRuntimeClassId& mrpt::obs::CObservation2DRangeScan::GetRuntimeClassIdStatic ( )
static

◆ getScanIntensity()

int CObservation2DRangeScan::getScanIntensity ( const size_t  i) const

Definition at line 515 of file CObservation2DRangeScan.cpp.

References ASSERT_BELOW_.

◆ getScanProperties()

void CObservation2DRangeScan::getScanProperties ( T2DScanProperties p) const

Fill out a T2DScanProperties structure with the parameters of this scan.

Definition at line 444 of file CObservation2DRangeScan.cpp.

Referenced by mrpt::obs::CSinCosLookUpTableFor2DScans::getSinCosForScan().

◆ getScanRange()

float CObservation2DRangeScan::getScanRange ( const size_t  i) const

◆ getScanRangeValidity()

bool CObservation2DRangeScan::getScanRangeValidity ( const size_t  i) const

Definition at line 526 of file CObservation2DRangeScan.cpp.

References ASSERT_BELOW_.

◆ getScanSize()

size_t CObservation2DRangeScan::getScanSize ( ) const

Get number of scan rays.

Definition at line 554 of file CObservation2DRangeScan.cpp.

Referenced by mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan().

◆ getSensorPose() [1/2]

void CObservation::getSensorPose ( mrpt::math::TPose3D out_sensorPose) const
inherited

A general method to retrieve the sensor pose on the robot.

Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.

See also
setSensorPose

Definition at line 26 of file CObservation.cpp.

◆ getSensorPose() [2/2]

void mrpt::obs::CObservation2DRangeScan::getSensorPose ( mrpt::poses::CPose3D out_sensorPose) const
inlineoverridevirtual

A general method to retrieve the sensor pose on the robot.

Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.

See also
setSensorPose

Implements mrpt::obs::CObservation.

Definition at line 216 of file CObservation2DRangeScan.h.

References sensorPose.

◆ getTimeStamp()

mrpt::system::TTimeStamp mrpt::obs::CObservation::getTimeStamp ( ) const
inlineinherited

Returns CObservation::timestamp for all kind of observations.

See also
getOriginalReceivedTimeStamp()

Definition at line 66 of file CObservation.h.

References mrpt::obs::CObservation::timestamp.

◆ hasIntensity()

bool CObservation2DRangeScan::hasIntensity ( ) const

Return true if scan has intensity.

Definition at line 259 of file CObservation2DRangeScan.cpp.

◆ insertObservationInto()

template<class METRICMAP >
bool mrpt::obs::CObservation::insertObservationInto ( METRICMAP *  theMap,
const mrpt::poses::CPose3D robotPose = nullptr 
) const
inlineinherited

This method is equivalent to:

map->insertObservation(this, robotPose)
Parameters
theMapThe map where this observation is to be inserted: the map will be updated.
robotPoseThe pose of the robot base for this observation, relative to the target metric map. Set to nullptr (default) to use (0,0,0deg)
Returns
Returns true if the map has been updated, or false if this observations has nothing to do with a metric map (for example, a sound observation).

See: Maps and observations compatibility matrix

See also
CMetricMap, CMetricMap::insertObservation

Definition at line 99 of file CObservation.h.

Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference().

◆ internal_buildAuxPointsMap()

void CObservation2DRangeScan::internal_buildAuxPointsMap ( const void options = nullptr) const
protected

Internal method, used from buildAuxPointsMap()

Definition at line 432 of file CObservation2DRangeScan.cpp.

References mrpt::obs::ptr_internal_build_points_map_from_scan2D.

Referenced by buildAuxPointsMap().

◆ isPlanarScan()

bool CObservation2DRangeScan::isPlanarScan ( const double  tolerance = 0) const

◆ load()

virtual void mrpt::obs::CObservation::load ( ) const
inlinevirtualinherited

Makes sure all images and other fields which may be externally stored are loaded in memory.

Note that for all CImages, calling load() is not required since the images will be automatically loaded upon first access, so load() shouldn't be needed to be called in normal cases by the user. If all the data were alredy loaded or this object has no externally stored data fields, calling this method has no effects.

See also
unload

Reimplemented in mrpt::obs::CObservation3DRangeScan.

Definition at line 154 of file CObservation.h.

◆ loadFromVectors()

void CObservation2DRangeScan::loadFromVectors ( size_t  nRays,
const float *  scanRanges,
const char *  scanValidity 
)

◆ operator delete() [1/3]

void mrpt::obs::CObservation2DRangeScan::operator delete ( void memory,
void ptr 
)
inlinenoexcept

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator delete() [2/3]

void mrpt::obs::CObservation2DRangeScan::operator delete ( void ptr)
inlinenoexcept

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator delete() [3/3]

void mrpt::obs::CObservation2DRangeScan::operator delete ( void ptr,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator delete[]()

void mrpt::obs::CObservation2DRangeScan::operator delete[] ( void ptr)
inlinenoexcept

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator new() [1/3]

void* mrpt::obs::CObservation2DRangeScan::operator new ( size_t  size)
inline

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator new() [2/3]

void* mrpt::obs::CObservation2DRangeScan::operator new ( size_t  size,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator new() [3/3]

static void* mrpt::obs::CObservation2DRangeScan::operator new ( size_t  size,
void ptr 
)
inlinestatic

Definition at line 58 of file CObservation2DRangeScan.h.

◆ operator new[]()

void* mrpt::obs::CObservation2DRangeScan::operator new[] ( size_t  size)
inline

Definition at line 58 of file CObservation2DRangeScan.h.

◆ resizeScan()

void CObservation2DRangeScan::resizeScan ( const size_t  len)

◆ resizeScanAndAssign()

void CObservation2DRangeScan::resizeScanAndAssign ( const size_t  len,
const float  rangeVal,
const bool  rangeValidity,
const int32_t  rangeIntensity = 0 
)

Resizes all data vectors to allocate a given number of scan rays and assign default values.

Definition at line 545 of file CObservation2DRangeScan.cpp.

Referenced by mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), and mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple().

◆ serializeFrom()

void CObservation2DRangeScan::serializeFrom ( mrpt::serialization::CArchive in,
uint8_t  serial_version 
)
overrideprotectedvirtual

Pure virtual method for reading (deserializing) from an abstract archive.

Users don't call this method directly. Instead, use stream >> object;.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any I/O error

Implements mrpt::serialization::CSerializable.

Definition at line 93 of file CObservation2DRangeScan.cpp.

References DEG2RAD, and MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION.

◆ serializeGetVersion()

uint8_t CObservation2DRangeScan::serializeGetVersion ( ) const
overrideprotectedvirtual

Must return the current versioning number of the object.

Start in zero for new classes, and increments each time there is a change in the stored format.

Implements mrpt::serialization::CSerializable.

Definition at line 39 of file CObservation2DRangeScan.cpp.

◆ serializeTo()

void CObservation2DRangeScan::serializeTo ( mrpt::serialization::CArchive out) const
overrideprotectedvirtual

Pure virtual method for writing (serializing) to an abstract archive.

Users don't call this method directly. Instead, use stream << object;.

Exceptions
std::exceptionOn any I/O error

Implements mrpt::serialization::CSerializable.

Definition at line 40 of file CObservation2DRangeScan.cpp.

References ASSERT_, mrpt::serialization::CArchive::WriteBuffer(), and mrpt::serialization::CArchive::WriteBufferFixEndianness().

◆ setScanHasIntensity()

void CObservation2DRangeScan::setScanHasIntensity ( bool  setHasIntensityFlag)

Marks this scan as having or not intensity data.

Definition at line 260 of file CObservation2DRangeScan.cpp.

Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple().

◆ setScanIntensity()

void CObservation2DRangeScan::setScanIntensity ( const size_t  i,
const int  val 
)

Definition at line 520 of file CObservation2DRangeScan.cpp.

References ASSERT_BELOW_, and val.

Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple().

◆ setScanRange()

void CObservation2DRangeScan::setScanRange ( const size_t  i,
const float  val 
)

◆ setScanRangeValidity()

void CObservation2DRangeScan::setScanRangeValidity ( const size_t  i,
const bool  val 
)

◆ setSensorPose() [1/2]

void CObservation::setSensorPose ( const mrpt::math::TPose3D newSensorPose)
inherited

A general method to change the sensor pose on the robot.

Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.

See also
getSensorPose

Definition at line 33 of file CObservation.cpp.

◆ setSensorPose() [2/2]

void mrpt::obs::CObservation2DRangeScan::setSensorPose ( const mrpt::poses::CPose3D newSensorPose)
inlineoverridevirtual

A general method to change the sensor pose on the robot.

Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.

See also
getSensorPose

Implements mrpt::obs::CObservation.

Definition at line 220 of file CObservation2DRangeScan.h.

References sensorPose.

◆ swap()

void CObservation::swap ( CObservation o)
protectedinherited

Swap with another observation, ONLY the data defined here in the base class CObservation.

It's protected since it'll be only called from child classes that should know what else to swap appart from these common data.

Definition at line 38 of file CObservation.cpp.

References mrpt::obs::CObservation::sensorLabel, and mrpt::obs::CObservation::timestamp.

Referenced by mrpt::obs::CObservationStereoImages::swap(), and mrpt::obs::CObservation3DRangeScan::swap().

◆ truncateByDistanceAndAngle()

void CObservation2DRangeScan::truncateByDistanceAndAngle ( float  min_distance,
float  max_angle,
float  min_height = 0,
float  max_height = 0,
float  h = 0 
)

A general method to truncate the scan by defining a minimum valid distance and a maximum valid angle as well as minimun and maximum heights (NOTE: the laser z-coordinate must be provided).

Definition at line 65 of file CObservation2DRangeScan.cpp.

References ASSERT_, and mrpt::poses::CPose3D::size().

◆ unload()

virtual void mrpt::obs::CObservation::unload ( )
inlinevirtualinherited

Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).

See also
load

Reimplemented in mrpt::obs::CObservation3DRangeScan.

Definition at line 161 of file CObservation.h.

◆ writeToMatlab()

virtual mxArray* mrpt::serialization::CSerializable::writeToMatlab ( ) const
inlinevirtualinherited

Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.

Returns
A new mxArray (caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB.

Definition at line 70 of file CSerializable.h.

Member Data Documentation

◆ _init_CObservation2DRangeScan

mrpt::rtti::CLASSINIT mrpt::obs::CObservation2DRangeScan::_init_CObservation2DRangeScan
staticprotected

Definition at line 58 of file CObservation2DRangeScan.h.

◆ aperture

float mrpt::obs::CObservation2DRangeScan::aperture {M_PIf}

◆ beamAperture

float mrpt::obs::CObservation2DRangeScan::beamAperture {0}

The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid.

Definition at line 139 of file CObservation2DRangeScan.h.

Referenced by mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), and mrpt::hwdrivers::CLMS100Eth::decodeScan().

◆ className

constexpr const char* mrpt::obs::CObservation2DRangeScan::className = "CObservation2DRangeScan"
staticconstexpr

Definition at line 58 of file CObservation2DRangeScan.h.

◆ deltaPitch

double mrpt::obs::CObservation2DRangeScan::deltaPitch {0}

If the laser gathers data by sweeping in the pitch/elevation angle, this holds the increment in "pitch" (=-"elevation") between the beginning and the end of the scan (the sensorPose member stands for the pose at the beginning of the scan).

Definition at line 144 of file CObservation2DRangeScan.h.

Referenced by FAddUntracedLines::operator()(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

◆ intensity

The intensity values of the scan.

If available, must have same length than validRange

Definition at line 111 of file CObservation2DRangeScan.h.

◆ m_cachedMap

mrpt::maps::CMetricMap::Ptr mrpt::obs::CObservation2DRangeScan::m_cachedMap
mutableprotected

A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap().

It's a generic smart pointer to avoid depending here in the library mrpt-obs on classes on other libraries.

Definition at line 162 of file CObservation2DRangeScan.h.

Referenced by buildAuxPointsMap(), and getAuxPointsMap().

◆ m_has_intensity

bool mrpt::obs::CObservation2DRangeScan::m_has_intensity {false}
private

Whether the intensity values are present or not.

If not, space is saved during serialization.

Definition at line 73 of file CObservation2DRangeScan.h.

◆ m_intensity

mrpt::aligned_std_vector<int32_t> mrpt::obs::CObservation2DRangeScan::m_intensity
private

The intensity values of the scan.

If available, must have same length than validRange

Definition at line 67 of file CObservation2DRangeScan.h.

◆ m_scan

mrpt::aligned_std_vector<float> mrpt::obs::CObservation2DRangeScan::m_scan
private

The range values of the scan, in meters.

Must have same length than validRange

Definition at line 64 of file CObservation2DRangeScan.h.

◆ m_validRange

mrpt::aligned_std_vector<char> mrpt::obs::CObservation2DRangeScan::m_validRange
private

It's false (=0) on no reflected rays, referenced to elements in scan.

Definition at line 70 of file CObservation2DRangeScan.h.

◆ maxRange

float mrpt::obs::CObservation2DRangeScan::maxRange {80.0f}

◆ rightToLeft

bool mrpt::obs::CObservation2DRangeScan::rightToLeft {true}

◆ runtimeClassId

const mrpt::rtti::TRuntimeClassId mrpt::obs::CObservation2DRangeScan::runtimeClassId
staticprotected

Definition at line 58 of file CObservation2DRangeScan.h.

◆ scan

mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector<float> > mrpt::obs::CObservation2DRangeScan::scan {m_scan}

◆ sensorLabel

std::string mrpt::obs::CObservation::sensorLabel
inherited

An arbitrary label that can be used to identify the sensor.

Definition at line 62 of file CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::obs::CObservation6DFeatures::serializeFrom(), mrpt::obs::CObservation3DRangeScan::serializeFrom(), mrpt::obs::CObservation6DFeatures::serializeTo(), mrpt::obs::CObservation3DRangeScan::serializeTo(), and mrpt::obs::CObservation::swap().

◆ sensorPose

mrpt::poses::CPose3D mrpt::obs::CObservation2DRangeScan::sensorPose

The 6D pose of the sensor on the robot at the moment of starting the scan.

Definition at line 133 of file CObservation2DRangeScan.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), getSensorPose(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::COccupancyGridMap2D::internal_canComputeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::COccupancyGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), FAddUntracedLines::operator()(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), mrpt::opengl::CPlanarLaserScan::render_dl(), run_rnav_test(), setSensorPose(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

◆ stdError

float mrpt::obs::CObservation2DRangeScan::stdError {0.01f}

◆ timestamp

mrpt::system::TTimeStamp mrpt::obs::CObservation::timestamp {mrpt::system::now()}
inherited

The associated UTC time-stamp.

Where available, this should contain the accurate satellite-based timestamp of the sensor reading.

See also
getOriginalReceivedTimeStamp(), getTimeStamp()

Definition at line 60 of file CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::detectors::CObjectDetection::detectObjects(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::obs::CObservation::getOriginalReceivedTimeStamp(), mrpt::obs::CObservation::getTimeStamp(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::obs::CObservation6DFeatures::serializeFrom(), mrpt::obs::CObservation3DRangeScan::serializeFrom(), mrpt::obs::CObservation6DFeatures::serializeTo(), mrpt::obs::CObservation3DRangeScan::serializeTo(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::obs::CObservation::swap(), and velodyne_scan_to_pointcloud().

◆ validRange

mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector<char> > mrpt::obs::CObservation2DRangeScan::validRange {m_validRange}
mrpt::maps::CMetricMap::insertObservation
bool insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
Insert the observation information into this map.
Definition: CMetricMap.cpp:95
mrpt::maps::CPointsMap
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors.
Definition: CPointsMap.h:64



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST