27 virtual unsigned int getSizeX()
const = 0;
28 virtual unsigned int getSizeY()
const = 0;
29 virtual float getCellAsFloat(
unsigned int cx,
unsigned int cy)
const = 0;
47 return const_cast<std::vector<T>&
>(
m_map);
56 double x_min = -10.0,
double x_max = 10.0,
double y_min = -10.0f,
57 double y_max = 10.0f,
double resolution = 0.10f)
67 setSize(x_min, x_max, y_min, y_max, resolution);
83 const double x_min,
const double x_max,
const double y_min,
84 const double y_max,
const double resolution,
85 const T* fill_value =
nullptr)
120 it !=
m_map.end(); ++it)
128 double new_x_min,
double new_x_max,
double new_y_min,
double new_y_max,
129 const T& defaultValueNewCells,
double additionalMarginMeters = 2.0)
142 if (additionalMarginMeters > 0)
145 new_x_min = floor(new_x_min - additionalMarginMeters);
147 new_x_max = ceil(new_x_max + additionalMarginMeters);
149 new_y_min = floor(new_y_min - additionalMarginMeters);
151 new_y_max = ceil(new_y_max + additionalMarginMeters);
177 typename std::vector<T> new_map;
178 new_map.resize(new_size_x * new_size_y, defaultValueNewCells);
187 (new_map.begin() + extra_x_izq +
188 (
y + extra_y_arr) * new_size_x);
215 if (cx < 0 || cx >= static_cast<int>(
m_size_x))
return nullptr;
216 if (cy < 0 || cy >= static_cast<int>(
m_size_y))
return nullptr;
224 if (cx < 0 || cx >= static_cast<int>(
m_size_x))
return nullptr;
225 if (cy < 0 || cy >= static_cast<int>(
m_size_y))
return nullptr;
243 inline const T*
cellByIndex(
unsigned int cx,
unsigned int cy)
const 281 inline void idx2cxcy(
const int& idx,
int& cx,
int& cy)
const 312 if (
m_map.empty())
return;
314 for (
size_t cy = 0; cy <
m_size_y; cy++)
315 for (
size_t cx = 0; cx <
m_size_x; cx++) m.set_unsafe(cy, cx, *
c++);
328 virtual unsigned int getSizeX()
const {
return m_obj.getSizeX(); }
329 virtual unsigned int getSizeY()
const {
return m_obj.getSizeY(); }
330 virtual float getCellAsFloat(
unsigned int cx,
unsigned int cy)
const 332 return m_obj.cell2float(
333 m_obj.m_map[cx + cy * m_obj.getSizeX()]);
337 aux_saver aux(*
this);
338 return aux.saveToTextFile(fileName);
342 template <
class STREAM>
347 out << static_cast<uint32_t>(
m_size_x)
350 template <
class STREAM>
353 if (!cast_from_float)
360 float xmin, xmax, ymin, ymax,
res;
361 in >> xmin >> xmax >> ymin >> ymax >>
res;
372 m_map.resize(nX * nY);
std::vector< T > m_map
The cells.
void clear()
Erase the contents of all the cells.
double getYMax() const
Returns the "y" coordinate of bottom side of grid map.
int y2idx(double y) const
A 2D grid of dynamic size which stores any kind of data at each cell.
void fill(const T &value)
Fills all the cells with the same value.
double getResolution() const
Returns the resolution of the grid map.
double getYMin() const
Returns the "y" coordinate of top side of grid map.
void dyngridcommon_writeToStream(STREAM &out) const
double idx2x(int cx) const
Transform a cell index into a coordinate value of the cell central point.
GLsizei GLsizei GLuint * obj
std::vector< T > & m_map_castaway_const() const
Used only from logically const method that really need to modify the object.
double idx2y(int cy) const
void setSize(const double x_min, const double x_max, const double y_min, const double y_max, const double resolution, const T *fill_value=nullptr)
Changes the size of the grid, ERASING all previous contents.
int xy2idx(double x, double y) const
double getXMin() const
Returns the "x" coordinate of left side of grid map.
bool saveToTextFile(const std::string &fileName) const
virtual float cell2float(const T &) const
The user must implement this in order to provide "saveToTextFile" a way to convert each cell into a n...
T * cellByPos(double x, double y)
Returns a pointer to the contents of a cell given by its coordinates, or nullptr if it is out of the ...
virtual void resize(double new_x_min, double new_x_max, double new_y_min, double new_y_max, const T &defaultValueNewCells, double additionalMarginMeters=2.0)
Changes the size of the grid, maintaining previous contents.
void getAsMatrix(MAT &m) const
Get the entire grid as a matrix.
const T * cellByPos(double x, double y) const
T * cellByIndex(unsigned int cx, unsigned int cy)
Returns a pointer to the contents of a cell given by its cell indexes, or nullptr if it is out of the...
size_t getSizeX() const
Returns the horizontal size of grid map in cells count.
void dyngridcommon_readFromStream(STREAM &in, bool cast_from_float=false)
GLsizei const GLchar ** string
size_t getSizeY() const
Returns the vertical size of grid map in cells count.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CDynamicGrid(double x_min=-10.0, double x_max=10.0, double y_min=-10.0f, double y_max=10.0f, double resolution=0.10f)
Constructor.
virtual float getCellAsFloat(unsigned int cx, unsigned int cy) const =0
bool saveToTextFile(const std::string &fileName) const
Saves a float representation of the grid (via "cell2float()") to a text file.
int x2idx(double x) const
Transform a coordinate values into cell indexes.
double getXMax() const
Returns the "x" coordinate of right side of grid map.
virtual ~CDynamicGrid()
Destructor.
GLsizei const GLfloat * value
void idx2cxcy(const int &idx, int &cx, int &cy) const
Transform a global (linear) cell index value into its corresponding (x,y) cell indexes.
unsigned __int32 uint32_t
virtual unsigned int getSizeX() const =0
const T * cellByIndex(unsigned int cx, unsigned int cy) const
Returns a pointer to the contents of a cell given by its cell indexes, or nullptr if it is out of the...
virtual unsigned int getSizeY() const =0
int round(const T value)
Returns the closer integer (int) to x.