37#include <gtest/gtest.h>
40#include <rclcpp/rclcpp.hpp>
44TEST(TestVoxelGrid, TestReadWrite)
63 for (
int x = 0; x < num_x; ++x)
65 for (
int y = 0; y < num_y; ++y)
67 for (
int z = 0; z < num_z; ++z)
69 EXPECT_EQ(vg.
getCell(x, y, z), 0);
83 for (
int x = 0; x < num_x; ++x)
85 for (
int y = 0; y < num_y; ++y)
87 for (
int z = 0; z < num_z; ++z)
97 for (
int x = 0; x < num_x; ++x)
99 for (
int y = 0; y < num_y; ++y)
101 for (
int z = 0; z < num_z; ++z)
103 EXPECT_EQ(i, vg.
getCell(x, y, z));
112 testing::InitGoogleTest(&argc, argv);
113 return RUN_ALL_TESTS();
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
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.
void reset(const T &initial)
Sets every cell in the voxel grid to the supplied data.
Namespace for holding classes that generate distance fields.
int main(int argc, char **argv)
TEST(TestVoxelGrid, TestReadWrite)