00001 #include <gtest/gtest.h> 00002 00003 #include "Map_test.h" 00004 00005 bool test_expansion_by_cell_update(const DiscretePoint2D& Cell_coor, MapParams expected_param) { 00006 GridMap map(std::shared_ptr<GridCellFactory>(new TinyBaseCellFactory), {1,1,1}); 00007 00008 map.update_cell(Cell_coor, {0.5, 0.5}); 00009 MapParams param(map.height(), map.width(), map.map_center_x(), map.map_center_y()); 00010 00011 return param == expected_param; 00012 } 00013 00014 TEST(AutoExpandbleMapBaseTests, Expand_Right) { 00015 EXPECT_TRUE(test_expansion_by_cell_update({2,0}, {1,4,0,0})); 00016 } 00017 00018 TEST(AutoExpandbleMapBaseTests, Expand_Top) { 00019 EXPECT_TRUE(test_expansion_by_cell_update({0,2}, {4,1,0,0})); 00020 } 00021 00022 TEST(AutoExpandbleMapBaseTests, Expand_Left) { 00023 EXPECT_TRUE(test_expansion_by_cell_update({-2,0}, {1,4,3,0})); 00024 } 00025 00026 TEST(AutoExpandbleMapBaseTests, Expand_Down) { 00027 EXPECT_TRUE(test_expansion_by_cell_update({0,-2}, {4,1,0,3})); 00028 } 00029 00030 TEST(AutoExpandbleMapBaseTests, Expand_Right_Top) { 00031 EXPECT_TRUE(test_expansion_by_cell_update({2,2}, {4,4,0,0})); 00032 } 00033 00034 TEST(AutoExpandbleMapBaseTests, Expand_Right_Down) { 00035 EXPECT_TRUE(test_expansion_by_cell_update({2,-2}, {4,4,0,3})); 00036 } 00037 00038 TEST(AutoExpandbleMapBaseTests, Expand_Left_Top) { 00039 EXPECT_TRUE(test_expansion_by_cell_update({-2,2}, {4,4,3,0})); 00040 } 00041 00042 TEST(AutoExpandbleMapBaseTests, Expand_Left_Down) { 00043 EXPECT_TRUE(test_expansion_by_cell_update({-2,-2}, {4,4,3,3})); 00044 } 00045 00046 TEST(AutoExpandbleMapBaseTests, NoExpand) { 00047 EXPECT_TRUE(test_expansion_by_cell_update({0,0}, {1,1,0,0})); 00048 } 00049 00050 TEST(AutoExpandbleMapBaseTests, CheckCellsValue) { 00051 GridMap map(std::shared_ptr<GridCellFactory>(new TinyBaseCellFactory), {1,1,1}); 00052 map.update_cell({5, 5}, {0.5, 0.5}); 00053 bool not_change = test_CellValueNotChange(map); 00054 EXPECT_TRUE(not_change); 00055 } 00056 00057 int main (int argc, char *argv[]) { 00058 ::testing::InitGoogleTest(&argc, argv); 00059 return RUN_ALL_TESTS(); 00060 }