Go to the documentation of this file.
37 #include <gtest/gtest.h>
44 TEST(TestVoxelGrid, TestReadWrite)
63 for (
int x = 0;
x < num_x;
x++)
64 for (
int y = 0;
y < num_y;
y++)
65 for (
int z = 0;
z < num_z;
z++)
79 for (
int x = 0;
x < num_x;
x++)
80 for (
int y = 0;
y < num_y;
y++)
81 for (
int z = 0;
z < num_z;
z++)
89 for (
int x = 0;
x < num_x;
x++)
90 for (
int y = 0;
y < num_y;
y++)
91 for (
int z = 0;
z < num_z;
z++)
98 int main(
int argc,
char** argv)
100 testing::InitGoogleTest(&argc, argv);
101 return RUN_ALL_TESTS();
int main(int argc, char **argv)
void reset(const T &initial)
Sets every cell in the voxel grid to the supplied data.
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
Namespace for holding classes that generate distance fields.
TEST(TestVoxelGrid, TestReadWrite)
int getNumCells(Dimension dim) const
Gets the number of cells in the indicated dimension.
T & getCell(int x, int y, int z)
Gives the value of the given location (x,y,z) in the discretized voxel grid space.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15