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:
scan
, intensity
, validRange
or (preferred) with the new get_*
, set_*
and resize()
methods:Definition at line 43 of file obs/CObservation2DRangeScan.h.
#include <mrpt/obs/CObservation2DRangeScan.h>
Public Types | |
typedef std::vector< mrpt::math::CPolygon > | TListExclusionAreas |
Used in filterByExclusionAreas. More... | |
typedef std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > > > | TListExclusionAreasWithRanges |
Used in filterByExclusionAreas. More... | |
Public Member Functions | |
void * | operator new (size_t size) |
void * | operator new[] (size_t size) |
void | operator delete (void *ptr) throw () |
void | operator delete[] (void *ptr) throw () |
void | operator delete (void *memory, void *ptr) throw () |
void * | operator new (size_t size, const std::nothrow_t &) throw () |
void | operator delete (void *ptr, const std::nothrow_t &) throw () |
CObservation2DRangeScan () | |
Default constructor. More... | |
CObservation2DRangeScan (const CObservation2DRangeScan &o) | |
copy ctor More... | |
virtual | ~CObservation2DRangeScan () |
Destructor. 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 MRPT_OVERRIDE |
A general method to retrieve the sensor pose on the robot. More... | |
void | setSensorPose (const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE |
A general method to change the sensor pose on the robot. More... | |
void | getDescriptionAsText (std::ostream &o) const MRPT_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=NULL) 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 mxArray * | writeToMatlab () 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... | |
CObject * | clone () const |
Cloning interface for smart pointers. More... | |
Delayed-load manual control methods. | |
virtual void | load () const |
Makes sure all images and other fields which may be externally stored are loaded in memory. More... | |
virtual void | unload () |
Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect). More... | |
RTTI classes and functions | |
mrpt::utils::CObjectPtr | duplicateGetSmartPtr () const |
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). More... | |
Static Public Member Functions | |
static void * | operator new (size_t size, void *ptr) |
Static Public Attributes | |
static const mrpt::utils::TRuntimeClassId | classCObject |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCObservation |
RTTI stuff | |
static const mrpt::utils::TRuntimeClassId | classCSerializable |
Protected Member Functions | |
void | swap (CObservation &o) |
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. More... | |
CSerializable virtual methods | |
void | writeToStream (mrpt::utils::CStream &out, int *getVersion) const |
Introduces a pure virtual method responsible for writing to a CStream. More... | |
void | readFromStream (mrpt::utils::CStream &in, int version) |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More... | |
Private Attributes | |
std::vector< float > | m_scan |
The range values of the scan, in meters. Must have same length than validRange. More... | |
std::vector< int32_t > | m_intensity |
The intensity values of the scan. If available, must have same length than validRange. More... | |
std::vector< char > | m_validRange |
It's false (=0) on no reflected rays, referenced to elements in scan. More... | |
bool | m_has_intensity |
Whether the intensity values are present or not. If not, space is saved during serialization. More... | |
Data common to any observation | |
mrpt::system::TTimeStamp | timestamp |
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading. 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 | |
typedef CObservation2DRangeScanPtr | Ptr |
typedef CObservation2DRangeScanPtr | ConstPtr |
static mrpt::utils::CLASSINIT | _init_CObservation2DRangeScan |
static mrpt::utils::TRuntimeClassId | classCObservation2DRangeScan |
static const mrpt::utils::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. More... | |
static mrpt::utils::CObject * | CreateObject () |
static CObservation2DRangeScanPtr | Create () |
Scan data | |
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > | scan |
The range values of the scan, in meters. Must have same length than validRange. More... | |
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< int32_t > > | intensity |
The intensity values of the scan. If available, must have same length than validRange. More... | |
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< char > > | validRange |
It's false (=0) on no reflected rays, referenced to elements in scan. More... | |
float | aperture |
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees). More... | |
bool | rightToLeft |
The scanning direction: true=counterclockwise; false=clockwise. More... | |
float | maxRange |
The maximum range allowed by the device, in meters (e.g. 80m, 50m,...) More... | |
mrpt::poses::CPose3D | sensorPose |
The 6D pose of the sensor on the robot at the moment of starting the scan. More... | |
float | stdError |
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid. More... | |
float | beamAperture |
The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid. More... | |
double | deltaPitch |
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::CMetricMapPtr | 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 NULL otherwise. More... | |
template<class POINTSMAP > | |
const POINTSMAP * | buildAuxPointsMap (const void *options=NULL) const |
Returns a cached points map representing this laser scan, building it upon the first call. More... | |
void | internal_buildAuxPointsMap (const void *options=NULL) const |
Internal method, used from buildAuxPointsMap() More... | |
typedef CObservation2DRangeScanPtr mrpt::obs::CObservation2DRangeScan::ConstPtr |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
typedef CObservation2DRangeScanPtr mrpt::obs::CObservation2DRangeScan::Ptr |
A typedef for the associated smart pointer
Definition at line 46 of file obs/CObservation2DRangeScan.h.
typedef std::vector<mrpt::math::CPolygon> mrpt::obs::CObservation2DRangeScan::TListExclusionAreas |
Used in filterByExclusionAreas.
Definition at line 56 of file obs/CObservation2DRangeScan.h.
typedef std::vector<std::pair<mrpt::math::CPolygon,std::pair<double,double> > > mrpt::obs::CObservation2DRangeScan::TListExclusionAreasWithRanges |
Used in filterByExclusionAreas.
Definition at line 57 of file obs/CObservation2DRangeScan.h.
CObservation2DRangeScan::CObservation2DRangeScan | ( | ) |
Default constructor.
Definition at line 33 of file CObservation2DRangeScan.cpp.
CObservation2DRangeScan::CObservation2DRangeScan | ( | const CObservation2DRangeScan & | o | ) |
|
virtual |
Destructor.
Definition at line 65 of file CObservation2DRangeScan.cpp.
|
staticprotected |
|
inline |
Returns a cached points map representing this laser scan, building it upon the first call.
options | Can be NULL to use default point maps' insertion options, or a pointer to a "CPointsMap::TInsertionOptions" structure to override some params. Usage: mrpt::maps::CPointsMap *map = obs->buildAuxPointsMap<mrpt::maps::CPointsMap>(&options or NULL); |
Definition at line 125 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_Consensus(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_ConsensusOWA(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_likelihoodField_II(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_likelihoodField_Thrun(), mrpt::maps::CHeightGridMap2D_Base::dem_internal_insertObservation(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), and mrpt::slam::observationsOverlap().
|
inlineinherited |
|
static |
|
static |
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
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 162 of file CObject.h.
References mrpt::utils::CObjectPtr.
Referenced by mrpt::obs::CRawlog::addActions(), mrpt::slam::CIncrementalMapPartitioner::addMapFrame(), and mrpt::obs::CRawlog::addObservations().
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>.
Definition at line 382 of file CObservation2DRangeScan.cpp.
References aperture, ASSERT_, m_validRange, MRPT_END, MRPT_START, rightToLeft, scan, mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size(), validRange, and mrpt::math::wrapTo2Pi().
Referenced by mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAngles().
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").
Definition at line 362 of file CObservation2DRangeScan.cpp.
Referenced by mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAreas().
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.
Definition at line 300 of file CObservation2DRangeScan.cpp.
References aperture, ASSERT_, mrpt::poses::CPose3D::composePoint(), m_scan, m_validRange, MRPT_END, MRPT_START, rightToLeft, scan, sensorPose, mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size(), and validRange.
|
inline |
Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or NULL otherwise.
Usage:
Definition at line 112 of file obs/CObservation2DRangeScan.h.
|
virtual |
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
Reimplemented from mrpt::obs::CObservation.
Definition at line 477 of file CObservation2DRangeScan.cpp.
References aperture, deltaPitch, mrpt::format(), mrpt::obs::CObservation::getDescriptionAsText(), mrpt::poses::CPose3D::getHomogeneousMatrixVal(), hasIntensity(), m_intensity, maxRange, RAD2DEG, rightToLeft, scan, sensorPose, mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size(), stdError, and validRange.
|
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.
Reimplemented in mrpt::obs::CObservationGPS, and mrpt::obs::CObservationVelodyneScan.
Definition at line 58 of file obs/CObservation.h.
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::obs::CObservation.
int CObservation2DRangeScan::getScanIntensity | ( | const size_t | i | ) | const |
Definition at line 523 of file CObservation2DRangeScan.cpp.
References ASSERT_BELOW_, and m_intensity.
void CObservation2DRangeScan::getScanProperties | ( | T2DScanProperties & | p | ) | const |
Fill out a T2DScanProperties structure with the parameters of this scan.
Definition at line 461 of file CObservation2DRangeScan.cpp.
References mrpt::obs::T2DScanProperties::aperture, aperture, mrpt::obs::T2DScanProperties::rightToLeft, rightToLeft, scan, and mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size().
Referenced by mrpt::obs::CSinCosLookUpTableFor2DScans::getSinCosForScan().
float CObservation2DRangeScan::getScanRange | ( | const size_t | i | ) | const |
Definition at line 511 of file CObservation2DRangeScan.cpp.
References ASSERT_BELOW_, and m_scan.
Referenced by mrpt::hwdrivers::CLMS100Eth::decodeScan().
bool CObservation2DRangeScan::getScanRangeValidity | ( | const size_t | i | ) | const |
Definition at line 534 of file CObservation2DRangeScan.cpp.
References ASSERT_BELOW_, and m_validRange.
size_t CObservation2DRangeScan::getScanSize | ( | ) | const |
Get number of scan rays.
Definition at line 569 of file CObservation2DRangeScan.cpp.
References m_scan.
Referenced by mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan().
|
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.
Definition at line 38 of file CObservation.cpp.
|
inlinevirtual |
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.
Implements mrpt::obs::CObservation.
Definition at line 142 of file obs/CObservation2DRangeScan.h.
|
inlineinherited |
Returns CObservation::timestamp for all kind of observations.
Definition at line 56 of file obs/CObservation.h.
bool CObservation2DRangeScan::hasIntensity | ( | ) | const |
Return true if scan has intensity.
Definition at line 287 of file CObservation2DRangeScan.cpp.
References m_has_intensity.
Referenced by getDescriptionAsText(), readFromStream(), and writeToStream().
|
inlineinherited |
This method is equivalent to:
theMap | The map where this observation is to be inserted: the map will be updated. |
robotPose | The pose of the robot base for this observation, relative to the target metric map. Set to NULL (default) to use (0,0,0deg) |
See: Maps and observations compatibility matrix
Definition at line 77 of file obs/CObservation.h.
Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference().
|
protected |
Internal method, used from buildAuxPointsMap()
Definition at line 452 of file CObservation2DRangeScan.cpp.
References m_cachedMap, and mrpt::obs::ptr_internal_build_points_map_from_scan2D.
bool CObservation2DRangeScan::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).
Definition at line 282 of file CObservation2DRangeScan.cpp.
References mrpt::poses::CPose3D::isHorizontal(), and sensorPose.
Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_Consensus(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_ConsensusOWA(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_likelihoodField_II(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_likelihoodField_Thrun(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::maps::COccupancyGridMap2D::internal_canComputeObservationLikelihood(), mrpt::maps::COccupancyGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), and mrpt::maps::CPointsMap::internal_insertObservation().
|
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.
Reimplemented in mrpt::obs::CObservation3DRangeScan.
Definition at line 119 of file obs/CObservation.h.
void CObservation2DRangeScan::loadFromVectors | ( | size_t | nRays, |
const float * | scanRanges, | ||
const char * | scanValidity | ||
) |
Definition at line 574 of file CObservation2DRangeScan.cpp.
References ASSERT_, m_scan, m_validRange, and resizeScan().
Referenced by ICPTests::align2scans(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::decimateLaserScan(), and TEST().
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
inline |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
inline |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
inlinestatic |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
inline |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
inline |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
inline |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
protectedvirtual |
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On any error, see CStream::ReadBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 136 of file CObservation2DRangeScan.cpp.
References aperture, beamAperture, DEG2RAD, deltaPitch, hasIntensity(), m_cachedMap, m_intensity, m_scan, m_validRange, maxRange, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, resizeScan(), rightToLeft, scan, mrpt::obs::CObservation::sensorLabel, sensorPose, setScanHasIntensity(), stdError, mrpt::obs::CObservation::timestamp, and version.
void CObservation2DRangeScan::resizeScan | ( | const size_t | len | ) |
Resizes all data vectors to allocate a given number of scan rays.
Definition at line 545 of file CObservation2DRangeScan.cpp.
References mrpt::mrpt::utils::length2length4N(), m_intensity, m_scan, and m_validRange.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), loadFromVectors(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and readFromStream().
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 557 of file CObservation2DRangeScan.cpp.
References mrpt::mrpt::utils::length2length4N(), m_intensity, m_scan, and m_validRange.
Referenced by mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), and mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple().
void CObservation2DRangeScan::setScanHasIntensity | ( | bool | setHasIntensityFlag | ) |
Marks this scan as having or not intensity data.
Definition at line 291 of file CObservation2DRangeScan.cpp.
References m_has_intensity.
Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), and readFromStream().
void CObservation2DRangeScan::setScanIntensity | ( | const size_t | i, |
const int | val | ||
) |
Definition at line 528 of file CObservation2DRangeScan.cpp.
References ASSERT_BELOW_, m_intensity, and val.
Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple().
void CObservation2DRangeScan::setScanRange | ( | const size_t | i, |
const float | val | ||
) |
Definition at line 517 of file CObservation2DRangeScan.cpp.
References ASSERT_BELOW_, m_scan, and val.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), and mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()().
void CObservation2DRangeScan::setScanRangeValidity | ( | const size_t | i, |
const bool | val | ||
) |
Definition at line 539 of file CObservation2DRangeScan.cpp.
References ASSERT_BELOW_, m_validRange, and val.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), and mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()().
|
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.
Definition at line 45 of file CObservation.cpp.
|
inlinevirtual |
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.
Implements mrpt::obs::CObservation.
Definition at line 143 of file obs/CObservation2DRangeScan.h.
|
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 50 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().
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 105 of file CObservation2DRangeScan.cpp.
References aperture, ASSERT_, m_scan, m_validRange, scan, and mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size().
|
inlinevirtualinherited |
Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
Reimplemented in mrpt::obs::CObservation3DRangeScan.
Definition at line 123 of file obs/CObservation.h.
|
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.
mxArray
(caller is responsible of memory freeing) or NULL is class does not support conversion to MATLAB. Definition at line 79 of file CSerializable.h.
|
protectedvirtual |
Introduces a pure virtual method responsible for writing to a CStream.
This can not be used directly be users, instead use "stream << object;" for writing it to a stream.
out | The output binary stream where object must be dumped. |
getVersion | If NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data. |
std::exception | On any error, see CStream::WriteBuffer |
Implements mrpt::utils::CSerializable.
Definition at line 72 of file CObservation2DRangeScan.cpp.
References aperture, ASSERT_, beamAperture, deltaPitch, hasIntensity(), m_intensity, m_scan, m_validRange, maxRange, rightToLeft, scan, mrpt::obs::CObservation::sensorLabel, sensorPose, mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size(), stdError, mrpt::obs::CObservation::timestamp, validRange, version, mrpt::utils::CStream::WriteBuffer(), and mrpt::utils::CStream::WriteBufferFixEndianness().
|
staticprotected |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
float mrpt::obs::CObservation2DRangeScan::aperture |
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees).
Definition at line 81 of file obs/CObservation2DRangeScan.h.
Referenced by ICPTests::align2scans(), mrpt::obs::carmen_log_parse_line(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), filterByExclusionAngles(), filterByExclusionAreas(), getDescriptionAsText(), getScanProperties(), 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()(), readFromStream(), run_rnav_test(), TEST(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), truncateByDistanceAndAngle(), and writeToStream().
float mrpt::obs::CObservation2DRangeScan::beamAperture |
The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid.
Definition at line 86 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::hwdrivers::CLMS100Eth::decodeScan(), readFromStream(), and writeToStream().
|
staticinherited |
|
staticinherited |
Definition at line 43 of file obs/CObservation.h.
|
static |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
|
staticinherited |
Definition at line 42 of file CSerializable.h.
|
static |
Definition at line 46 of file obs/CObservation2DRangeScan.h.
double mrpt::obs::CObservation2DRangeScan::deltaPitch |
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 87 of file obs/CObservation2DRangeScan.h.
Referenced by getDescriptionAsText(), FAddUntracedLines::operator()(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), readFromStream(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), and writeToStream().
mrpt::utils::ContainerReadOnlyProxyAccessor<std::vector<int32_t> > mrpt::obs::CObservation2DRangeScan::intensity |
The intensity values of the scan. If available, must have same length than validRange.
Definition at line 73 of file obs/CObservation2DRangeScan.h.
|
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 100 of file obs/CObservation2DRangeScan.h.
Referenced by internal_buildAuxPointsMap(), and readFromStream().
|
private |
Whether the intensity values are present or not. If not, space is saved during serialization.
Definition at line 53 of file obs/CObservation2DRangeScan.h.
Referenced by hasIntensity(), and setScanHasIntensity().
|
private |
The intensity values of the scan. If available, must have same length than validRange.
Definition at line 51 of file obs/CObservation2DRangeScan.h.
Referenced by getDescriptionAsText(), getScanIntensity(), readFromStream(), resizeScan(), resizeScanAndAssign(), setScanIntensity(), and writeToStream().
|
private |
The range values of the scan, in meters. Must have same length than validRange.
Definition at line 50 of file obs/CObservation2DRangeScan.h.
Referenced by CObservation2DRangeScan(), filterByExclusionAreas(), getScanRange(), getScanSize(), loadFromVectors(), readFromStream(), resizeScan(), resizeScanAndAssign(), setScanRange(), truncateByDistanceAndAngle(), and writeToStream().
|
private |
It's false (=0) on no reflected rays, referenced to elements in scan.
Definition at line 52 of file obs/CObservation2DRangeScan.h.
Referenced by filterByExclusionAngles(), filterByExclusionAreas(), getScanRangeValidity(), loadFromVectors(), readFromStream(), resizeScan(), resizeScanAndAssign(), setScanRangeValidity(), truncateByDistanceAndAngle(), and writeToStream().
float mrpt::obs::CObservation2DRangeScan::maxRange |
The maximum range allowed by the device, in meters (e.g. 80m, 50m,...)
Definition at line 83 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::obs::CObservation2DRangeScanWithUncertainty::evaluateScanLikelihood(), getDescriptionAsText(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), readFromStream(), run_rnav_test(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), and writeToStream().
bool mrpt::obs::CObservation2DRangeScan::rightToLeft |
The scanning direction: true=counterclockwise; false=clockwise.
Definition at line 82 of file obs/CObservation2DRangeScan.h.
Referenced by ICPTests::align2scans(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), filterByExclusionAngles(), filterByExclusionAreas(), getDescriptionAsText(), getScanProperties(), 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()(), readFromStream(), TEST(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), and writeToStream().
mrpt::utils::ContainerReadOnlyProxyAccessor<std::vector<float> > mrpt::obs::CObservation2DRangeScan::scan |
The range values of the scan, in meters. Must have same length than validRange.
Definition at line 69 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::decimateLaserScan(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::obs::CObservation2DRangeScanWithUncertainty::evaluateScanLikelihood(), filterByExclusionAngles(), filterByExclusionAreas(), getDescriptionAsText(), getScanProperties(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), FAddUntracedLines::operator()(), readFromStream(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), truncateByDistanceAndAngle(), and writeToStream().
|
inherited |
An arbitrary label that can be used to identify the sensor.
Definition at line 53 of file obs/CObservation.h.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), 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::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::obs::CObservation6DFeatures::readFromStream(), mrpt::obs::CObservationStereoImages::readFromStream(), readFromStream(), mrpt::obs::CObservationVelodyneScan::readFromStream(), mrpt::obs::CObservation3DRangeScan::readFromStream(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), mrpt::obs::CObservation6DFeatures::writeToStream(), mrpt::obs::CObservationStereoImages::writeToStream(), writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().
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 84 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), filterByExclusionAreas(), getDescriptionAsText(), 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(), isPlanarScan(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), FAddUntracedLines::operator()(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), readFromStream(), run_rnav_test(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), and writeToStream().
float mrpt::obs::CObservation2DRangeScan::stdError |
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
Definition at line 85 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::obs::CObservation2DRangeScanWithUncertainty::evaluateScanLikelihood(), getDescriptionAsText(), readFromStream(), and writeToStream().
|
inherited |
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading.
Definition at line 52 of file obs/CObservation.h.
Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservationVelodyneScan::TPointCloud::clear_deep(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), 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::obs::CObservationGasSensors::CMOSmodel::get_GasDistribution_estimation(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::obs::CObservationGasSensors::CMOSmodel::noise_filtering(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::obs::CObservation6DFeatures::readFromStream(), mrpt::obs::CObservationStereoImages::readFromStream(), readFromStream(), mrpt::obs::CObservationVelodyneScan::readFromStream(), mrpt::obs::CObservation3DRangeScan::readFromStream(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), velodyne_scan_to_pointcloud(), mrpt::obs::CObservation6DFeatures::writeToStream(), mrpt::obs::CObservationStereoImages::writeToStream(), writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().
mrpt::utils::ContainerReadOnlyProxyAccessor<std::vector<char> > mrpt::obs::CObservation2DRangeScan::validRange |
It's false (=0) on no reflected rays, referenced to elements in scan.
Definition at line 77 of file obs/CObservation2DRangeScan.h.
Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::decimateLaserScan(), mrpt::obs::CObservation2DRangeScanWithUncertainty::evaluateScanLikelihood(), filterByExclusionAngles(), filterByExclusionAreas(), getDescriptionAsText(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), FAddUntracedLines::operator()(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays(), and writeToStream().
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |