Class CWirelessPowerGridMap2D
Defined in File CWirelessPowerGridMap2D.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public mrpt::maps::CRandomFieldGridMap2D(Class CRandomFieldGridMap2D)
Class Documentation
-
class CWirelessPowerGridMap2D : public mrpt::maps::CRandomFieldGridMap2D
CWirelessPowerGridMap2D represents a PDF of wifi concentrations over a 2D area.
There are a number of methods available to build the wifi grid-map, depending on the value of “TMapRepresentation maptype” passed in the constructor (see CRandomFieldGridMap2D for a discussion).
Update the map with insertIndividualReading() or insertObservation()
See also
mrpt::maps::CRandomFieldGridMap2D, mrpt::maps::CMetricMap, mrpt::containers::CDynamicGrid, The application icp-slam, mrpt::maps::CMultiMetricMap
Public Functions
-
CWirelessPowerGridMap2D(TMapRepresentation mapType = mrKernelDM, double x_min = -2, double x_max = 2, double y_min = -2, double y_max = 2, double resolution = 0.1)
Constructor
-
~CWirelessPowerGridMap2D() override
Destructor
-
void getVisualizationInto(mrpt::viz::CSetOfObjects &outObj) const override
Returns a 3D object representing the map
Public Members
-
mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions insertionOptions
Protected Functions
-
inline virtual CRandomFieldGridMap2D::TInsertionOptionsCommon *getCommonInsertOptions() override
Get the part of the options common to all CRandomFieldGridMap2D classes
-
void internal_clear() override
Protected Attributes
-
double min_x = {-2}
-
double max_x = {2}
-
double min_y = {-2}
-
double max_y = {2}
-
double resolution = {0.10f}
-
mrpt::maps::CWirelessPowerGridMap2D::TMapRepresentation mapType = {CWirelessPowerGridMap2D::mrKernelDM}
The kind of map representation (see CWirelessPowerGridMap2D::CWirelessPowerGridMap2D)
-
mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions insertionOpts
-
struct TInsertionOptions : public mrpt::config::CLoadableOptions, public mrpt::maps::CRandomFieldGridMap2D::TInsertionOptionsCommon
Parameters related with inserting observations into the map:
-
CWirelessPowerGridMap2D(TMapRepresentation mapType = mrKernelDM, double x_min = -2, double x_max = 2, double y_min = -2, double y_max = 2, double resolution = 0.1)