moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
voxel_grid.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Mrinal Kalakrishnan, Acorn Pooley */
36
37#pragma once
38
39#include <algorithm>
40#include <cmath>
41#include <Eigen/Core>
43
44namespace distance_field
45{
48{
49 DIM_X = 0,
50 DIM_Y = 1,
51 DIM_Z = 2
52};
53
60template <typename T>
62{
63public:
65
91 VoxelGrid(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y,
92 double origin_z, T default_object);
93 virtual ~VoxelGrid();
94
102
120 void resize(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y,
121 double origin_z, T default_object);
122
136 const T& operator()(double x, double y, double z) const;
137 const T& operator()(const Eigen::Vector3d& pos) const;
138
156 T& getCell(int x, int y, int z);
157 T& getCell(const Eigen::Vector3i& pos);
158 const T& getCell(int x, int y, int z) const;
159 const T& getCell(const Eigen::Vector3i& pos) const;
160
179 void setCell(int x, int y, int z, const T& obj);
180 void setCell(const Eigen::Vector3i& pos, const T& obj);
181
187 void reset(const T& initial);
188
196 double getSize(Dimension dim) const;
197
203 double getResolution() const;
204
212 double getOrigin(Dimension dim) const;
213
221 int getNumCells(Dimension dim) const;
222
241 void gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const;
242 void gridToWorld(const Eigen::Vector3i& grid, Eigen::Vector3d& world) const;
243
260 bool worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const;
261 bool worldToGrid(const Eigen::Vector3d& world, Eigen::Vector3i& grid) const;
262
272 bool isCellValid(int x, int y, int z) const;
273 bool isCellValid(const Eigen::Vector3i& pos) const;
274
283 bool isCellValid(Dimension dim, int cell) const;
284
285protected:
286 T* data_;
289 double size_[3];
290 double resolution_;
292 double origin_[3];
293 double origin_minus_[3];
294 int num_cells_[3];
308 int ref(int x, int y, int z) const;
309
322 int getCellFromLocation(Dimension dim, double loc) const;
323
333 double getLocationFromCell(Dimension dim, int cell) const;
334};
335
337
338template <typename T>
339VoxelGrid<T>::VoxelGrid(double size_x, double size_y, double size_z, double resolution, double origin_x,
340 double origin_y, double origin_z, T default_object)
341 : data_(nullptr)
342{
343 resize(size_x, size_y, size_z, resolution, origin_x, origin_y, origin_z, default_object);
344}
345
346template <typename T>
347VoxelGrid<T>::VoxelGrid() : data_(nullptr)
348{
349 for (int i = DIM_X; i <= DIM_Z; ++i)
350 {
351 size_[i] = 0;
352 origin_[i] = 0;
353 origin_minus_[i] = 0;
354 num_cells_[i] = 0;
355 }
356 resolution_ = 1.0;
359 stride1_ = 0;
360 stride2_ = 0;
361}
362
363template <typename T>
364void VoxelGrid<T>::resize(double size_x, double size_y, double size_z, double resolution, double origin_x,
365 double origin_y, double origin_z, T default_object)
366{
367 delete[] data_;
368 data_ = nullptr;
369
370 size_[DIM_X] = size_x;
371 size_[DIM_Y] = size_y;
372 size_[DIM_Z] = size_z;
373 origin_[DIM_X] = origin_x;
374 origin_[DIM_Y] = origin_y;
375 origin_[DIM_Z] = origin_z;
376 origin_minus_[DIM_X] = origin_x - 0.5 * resolution;
377 origin_minus_[DIM_Y] = origin_y - 0.5 * resolution;
378 origin_minus_[DIM_Z] = origin_z - 0.5 * resolution;
379 num_cells_total_ = 1;
380 resolution_ = resolution;
381 oo_resolution_ = 1.0 / resolution_;
382 for (int i = DIM_X; i <= DIM_Z; ++i)
383 {
384 num_cells_[i] = size_[i] * oo_resolution_;
385 num_cells_total_ *= num_cells_[i];
386 }
387
388 default_object_ = default_object;
389
390 stride1_ = num_cells_[DIM_Y] * num_cells_[DIM_Z];
391 stride2_ = num_cells_[DIM_Z];
392
393 // initialize the data:
394 if (num_cells_total_ > 0)
395 data_ = new T[num_cells_total_];
396}
397
398template <typename T>
400{
401 delete[] data_;
402}
403
404template <typename T>
405inline bool VoxelGrid<T>::isCellValid(int x, int y, int z) const
406{
407 return (x >= 0 && x < num_cells_[DIM_X] && y >= 0 && y < num_cells_[DIM_Y] && z >= 0 && z < num_cells_[DIM_Z]);
408}
409
410template <typename T>
411inline bool VoxelGrid<T>::isCellValid(const Eigen::Vector3i& pos) const
412{
413 return isCellValid(pos.x(), pos.y(), pos.z());
414}
415
416template <typename T>
417inline bool VoxelGrid<T>::isCellValid(Dimension dim, int cell) const
418{
419 return cell >= 0 && cell < num_cells_[dim];
420}
421
422template <typename T>
423inline int VoxelGrid<T>::ref(int x, int y, int z) const
424{
425 return x * stride1_ + y * stride2_ + z;
426}
427
428template <typename T>
429inline double VoxelGrid<T>::getSize(Dimension dim) const
430{
431 return size_[dim];
432}
433
434template <typename T>
435inline double VoxelGrid<T>::getResolution() const
436{
437 return resolution_;
438}
439
440template <typename T>
441inline double VoxelGrid<T>::getOrigin(Dimension dim) const
442{
443 return origin_[dim];
444}
445
446template <typename T>
448{
449 return num_cells_[dim];
450}
451
452template <typename T>
453inline const T& VoxelGrid<T>::operator()(double x, double y, double z) const
454{
455 int cell_x = getCellFromLocation(DIM_X, x);
456 int cell_y = getCellFromLocation(DIM_Y, y);
457 int cell_z = getCellFromLocation(DIM_Z, z);
458 if (!isCellValid(cell_x, cell_y, cell_z))
459 return default_object_;
460 return getCell(cell_x, cell_y, cell_z);
461}
462
463template <typename T>
464inline const T& VoxelGrid<T>::operator()(const Eigen::Vector3d& pos) const
465{
466 return operator()(pos.x(), pos.y(), pos.z());
467}
468
469template <typename T>
470inline T& VoxelGrid<T>::getCell(int x, int y, int z)
471{
472 return data_[ref(x, y, z)];
473}
474
475template <typename T>
476inline const T& VoxelGrid<T>::getCell(int x, int y, int z) const
477{
478 return data_[ref(x, y, z)];
479}
480
481template <typename T>
482inline T& VoxelGrid<T>::getCell(const Eigen::Vector3i& pos)
483{
484 return data_[ref(pos.x(), pos.y(), pos.z())];
485}
486
487template <typename T>
488inline const T& VoxelGrid<T>::getCell(const Eigen::Vector3i& pos) const
489{
490 return data_[ref(pos.x(), pos.y(), pos.z())];
491}
492
493template <typename T>
494inline void VoxelGrid<T>::setCell(int x, int y, int z, const T& obj)
495{
496 data_[ref(x, y, z)] = obj;
497}
498
499template <typename T>
500inline void VoxelGrid<T>::setCell(const Eigen::Vector3i& pos, const T& obj)
501{
502 data_[ref(pos.x(), pos.y(), pos.z())] = obj;
503}
504
505template <typename T>
506inline int VoxelGrid<T>::getCellFromLocation(Dimension dim, double loc) const
507{
508 // This implements
509 //
510 // ( loc - origin )
511 // floor( ------------ + 0.5 )
512 // ( resolution )
513 //
514 // In other words, the rounded quantized location.
515 //
516 // For speed implemented like this:
517 //
518 // floor( ( loc - origin_minus ) * oo_resolution )
519 //
520 // where origin_minus = origin - 0.5*resolution
521 //
522 return int(floor((loc - origin_minus_[dim]) * oo_resolution_));
523}
524
525template <typename T>
526inline double VoxelGrid<T>::getLocationFromCell(Dimension dim, int cell) const
527{
528 return origin_[dim] + resolution_ * (double(cell));
529}
530
531template <typename T>
532inline void VoxelGrid<T>::reset(const T& initial)
533{
534 std::fill(data_, data_ + num_cells_total_, initial);
535}
536
537template <typename T>
538inline void VoxelGrid<T>::gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const
539{
540 world_x = getLocationFromCell(DIM_X, x);
541 world_y = getLocationFromCell(DIM_Y, y);
542 world_z = getLocationFromCell(DIM_Z, z);
543}
544
545template <typename T>
546inline void VoxelGrid<T>::gridToWorld(const Eigen::Vector3i& grid, Eigen::Vector3d& world) const
547{
548 world.x() = getLocationFromCell(DIM_X, grid.x());
549 world.y() = getLocationFromCell(DIM_Y, grid.y());
550 world.z() = getLocationFromCell(DIM_Z, grid.z());
551}
552
553template <typename T>
554inline bool VoxelGrid<T>::worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const
555{
556 x = getCellFromLocation(DIM_X, world_x);
557 y = getCellFromLocation(DIM_Y, world_y);
558 z = getCellFromLocation(DIM_Z, world_z);
559 return isCellValid(x, y, z);
560}
561
562template <typename T>
563inline bool VoxelGrid<T>::worldToGrid(const Eigen::Vector3d& world, Eigen::Vector3i& grid) const
564{
565 grid.x() = getCellFromLocation(DIM_X, world.x());
566 grid.y() = getCellFromLocation(DIM_Y, world.y());
567 grid.z() = getCellFromLocation(DIM_Z, world.z());
568 return isCellValid(grid.x(), grid.y(), grid.z());
569}
570
571} // namespace distance_field
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
double size_[3]
The size of each dimension in meters (in Dimension order)
int stride2_
The step to take when stepping between consecutive Y members given an X in the 1D array.
bool worldToGrid(double world_x, double world_y, double world_z, int &x, int &y, int &z) const
Converts from a world location to a set of integer indices. Does check whether or not the cell being ...
VoxelGrid()
Default constructor for the VoxelGrid.
const T & operator()(double x, double y, double z) const
Operator that gets the value of the given location (x, y, z) given the discretization of the volume....
double oo_resolution_
1.0/resolution_
T *** data_ptrs_
3D array of pointers to the data elements
int num_cells_total_
The total number of voxels in the grid.
int getNumCells(Dimension dim) const
Gets the number of cells in the indicated dimension.
int getCellFromLocation(Dimension dim, double loc) const
Gets the cell number from the location.
void setCell(const Eigen::Vector3i &pos, const T &obj)
double origin_minus_[3]
origin - 0.5/resolution
const T & getCell(const Eigen::Vector3i &pos) const
bool isCellValid(const Eigen::Vector3i &pos) const
bool isCellValid(Dimension dim, int cell) const
Checks if the indicated index is valid along a particular dimension.
double origin_[3]
The origin (minimum point) of each dimension in meters (in Dimension order)
int stride1_
The step to take when stepping between consecutive X members in the 1D array.
T & getCell(int x, int y, int z)
Gives the value of the given location (x,y,z) in the discretized voxel grid space.
double resolution_
The resolution of each dimension in meters (in Dimension order)
void setCell(int x, int y, int z, const T &obj)
Sets the value of the given location (x,y,z) in the discretized voxel grid space to supplied value.
void reset(const T &initial)
Sets every cell in the voxel grid to the supplied data.
double getLocationFromCell(Dimension dim, int cell) const
Gets the center of the cell in world coordinates along the given dimension. No validity check.
MOVEIT_DECLARE_PTR_MEMBER(VoxelGrid)
T & getCell(const Eigen::Vector3i &pos)
const T & operator()(const Eigen::Vector3d &pos) const
int num_cells_[3]
The number of cells in each dimension (in Dimension order)
double getOrigin(Dimension dim) const
Gets the origin (minimum point) of the indicated dimension.
const T & getCell(int x, int y, int z) const
T * data_
Storage for the full set of data elements.
bool isCellValid(int x, int y, int z) const
Checks if the given cell in integer coordinates is within the voxel grid.
T default_object_
The default object to return in case of out-of-bounds query.
bool worldToGrid(const Eigen::Vector3d &world, Eigen::Vector3i &grid) const
double getSize(Dimension dim) const
Gets the size in arbitrary units of the indicated dimension.
void gridToWorld(const Eigen::Vector3i &grid, Eigen::Vector3d &world) const
int ref(int x, int y, int z) const
Gets the 1D index into the array, with no validity check.
double getResolution() const
Gets the resolution in arbitrary consistent units.
VoxelGrid(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z, T default_object)
Constructor for the VoxelGrid.
void resize(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z, T default_object)
Resize the VoxelGrid.
void gridToWorld(int x, int y, int z, double &world_x, double &world_y, double &world_z) const
Converts grid coordinates to world coordinates.
Namespace for holding classes that generate distance fields.
Dimension
Specifies dimension of different axes.