00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00032 #include <gtest/gtest.h> 00033 00034 #include <distance_field/voxel_grid.h> 00035 #include <ros/ros.h> 00036 00037 using namespace distance_field; 00038 00039 TEST(TestVoxelGrid, TestReadWrite) 00040 { 00041 int i; 00042 int def=-100; 00043 VoxelGrid<int> vg(0.02,0.02,0.02,0.01,0,0,0, def); 00044 00045 int numX = vg.getNumCells(VoxelGrid<int>::DIM_X); 00046 int numY = vg.getNumCells(VoxelGrid<int>::DIM_Y); 00047 int numZ = vg.getNumCells(VoxelGrid<int>::DIM_Z); 00048 00049 // Check dimensions 00050 EXPECT_EQ(numX,2); 00051 EXPECT_EQ(numY,2); 00052 EXPECT_EQ(numZ,2); 00053 00054 // check initial values 00055 vg.reset(0); 00056 00057 i=0; 00058 for (int x=0; x<numX; x++) 00059 for (int y=0; y<numY; y++) 00060 for (int z=0; z<numZ; z++) 00061 { 00062 EXPECT_EQ( vg.getCell(x,y,z), 0); 00063 i++; 00064 } 00065 00066 // Check out-of-bounds query // FIXME-- this test fails!! 00067 //EXPECT_EQ( vg.getCell(999,9999,999), def ); 00068 //EXPECT_EQ( vg.getCell(numX+1,0,0), def); 00069 //EXPECT_EQ( vg.getCell(0,numY+1,0), def); 00070 //EXPECT_EQ( vg.getCell(0,0,numZ+1), def); 00071 00072 // Set values 00073 i=0; 00074 for (int x=0; x<numX; x++) 00075 for (int y=0; y<numY; y++) 00076 for (int z=0; z<numZ; z++) 00077 { 00078 vg.getCell(x,y,z) = i; 00079 i++; 00080 } 00081 00082 // check reset values 00083 i=0; 00084 for (int x=0; x<numX; x++) 00085 for (int y=0; y<numY; y++) 00086 for (int z=0; z<numZ; z++) 00087 { 00088 EXPECT_EQ(i, vg.getCell(x,y,z)); 00089 i++; 00090 } 00091 00092 } 00093 00094 int main(int argc, char **argv){ 00095 testing::InitGoogleTest(&argc, argv); 00096 return RUN_ALL_TESTS(); 00097 }