78 std::vector<std::pair<mrpt::math::CPolygon, std::pair<double, double>>>;
90 const size_t len,
const float rangeVal,
const bool rangeValidity,
91 const int32_t rangeIntensity = 0);
141 size_t nRays,
const float* scanRanges,
const char* scanValidity);
165 template <
class POINTSMAP>
168 return static_cast<const POINTSMAP*
>(
m_cachedMap.get());
183 template <
class POINTSMAP>
185 const void* options =
nullptr)
const 188 return static_cast<const POINTSMAP*
>(
m_cachedMap.get());
220 float min_distance,
float max_angle,
float min_height = 0,
221 float max_height = 0,
float h = 0);
243 const std::vector<std::pair<double, double>>& angles);
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...
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
float beamAperture
The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid...
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
void getScanProperties(T2DScanProperties &p) const
Fill out a T2DScanProperties structure with the parameters of this scan.
void setScanRange(const size_t i, const float val)
void setScanHasIntensity(bool setHasIntensityFlag)
Marks this scan as having or not intensity data.
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
size_t getScanSize() const
Get number of scan rays.
float maxRange
The maximum range allowed by the device, in meters (e.g.
std::vector< mrpt::math::CPolygon > TListExclusionAreas
Used in filterByExclusionAreas.
mrpt::maps::CMetricMap::Ptr m_cachedMap
A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap().
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" l...
Auxiliary struct that holds all the relevant geometry information about a 2D scan.
void internal_buildAuxPointsMap(const void *options=nullptr) const
Internal method, used from buildAuxPointsMap()
#define DECLARE_MEX_CONVERSION
This must be inserted if a custom conversion method for MEX API is implemented in the class...
DECLARE_MEXPLUS_FROM(mrpt::img::TCamera) namespace std
void setScanIntensity(const size_t i, const int val)
mrpt::aligned_std_vector< float > m_scan
The range values of the scan, in meters.
This namespace contains representation of robot actions and observations.
bool m_has_intensity
Whether the intensity values are present or not.
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...
const int32_t & getScanIntensity(const size_t i) const
The intensity values of the scan.
#define MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE(_TYPE, __NS)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
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 ...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > >> TListExclusionAreasWithRanges
Used in filterByExclusionAreas.
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
mrpt::aligned_std_vector< int32_t > m_intensity
The intensity values of the scan.
const float & getScanRange(const size_t i) const
The range values of the scan, in meters.
double deltaPitch
If the laser gathers data by sweeping in the pitch/elevation angle, this holds the increment in "pitc...
const POINTSMAP * getAuxPointsMap() const
Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or nullptr otherwise.
mrpt::aligned_std_vector< char > m_validRange
It's false (=0) on no reflected rays, referenced to elements in scan.
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
bool hasIntensity() const
Return true if scan has intensity.
void filterByExclusionAreas(const TListExclusionAreas &areas)
Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinate...
CObservation2DRangeScan()=default
Default constructor.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
void setScanRangeValidity(const size_t i, const bool val)
bool getScanRangeValidity(const size_t i) const
It's false (=0) on no reflected rays, referenced to elements in scan.