123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417 |
- #include <map>
- #include <cmath>
- #include <costmap_2d/costmap_2d.h>
- #include <costmap_2d/layered_costmap.h>
- #include <costmap_2d/obstacle_layer.h>
- #include <costmap_2d/inflation_layer.h>
- #include <costmap_2d/observation_buffer.h>
- #include <costmap_2d/testing_helper.h>
- #include <gtest/gtest.h>
- using namespace costmap_2d;
- using geometry_msgs::Point;
- std::vector<Point> setRadii(LayeredCostmap& layers, double length, double width, double inflation_radius)
- {
- std::vector<Point> polygon;
- Point p;
- p.x = width;
- p.y = length;
- polygon.push_back(p);
- p.x = width;
- p.y = -length;
- polygon.push_back(p);
- p.x = -width;
- p.y = -length;
- polygon.push_back(p);
- p.x = -width;
- p.y = length;
- polygon.push_back(p);
- layers.setFootprint(polygon);
- ros::NodeHandle nh;
- nh.setParam("/inflation_tests/inflation/inflation_radius", inflation_radius);
- return polygon;
- }
- void validatePointInflation(unsigned int mx, unsigned int my, Costmap2D* costmap, InflationLayer* ilayer, double inflation_radius)
- {
- bool* seen = new bool[costmap->getSizeInCellsX() * costmap->getSizeInCellsY()];
- memset(seen, false, costmap->getSizeInCellsX() * costmap->getSizeInCellsY() * sizeof(bool));
- std::map<double, std::vector<CellData> > m;
- CellData initial(costmap->getIndex(mx, my), mx, my, mx, my);
- m[0].push_back(initial);
- for (std::map<double, std::vector<CellData> >::iterator bin = m.begin(); bin != m.end(); ++bin)
- {
- for (int i = 0; i < bin->second.size(); ++i)
- {
- const CellData& cell = bin->second[i];
- if (!seen[cell.index_])
- {
- seen[cell.index_] = true;
- unsigned int dx = (cell.x_ > cell.src_x_) ? cell.x_ - cell.src_x_ : cell.src_x_ - cell.x_;
- unsigned int dy = (cell.y_ > cell.src_y_) ? cell.y_ - cell.src_y_ : cell.src_y_ - cell.y_;
- double dist = hypot(dx, dy);
- unsigned char expected_cost = ilayer->computeCost(dist);
- ASSERT_TRUE(costmap->getCost(cell.x_, cell.y_) >= expected_cost);
- if (dist > inflation_radius)
- {
- continue;
- }
- if (dist == bin->first)
- {
-
-
- dist += 0.001;
- }
- if (cell.x_ > 0)
- {
- CellData data(costmap->getIndex(cell.x_-1, cell.y_),
- cell.x_-1, cell.y_, cell.src_x_, cell.src_y_);
- m[dist].push_back(data);
- }
- if (cell.y_ > 0)
- {
- CellData data(costmap->getIndex(cell.x_, cell.y_-1),
- cell.x_, cell.y_-1, cell.src_x_, cell.src_y_);
- m[dist].push_back(data);
- }
- if (cell.x_ < costmap->getSizeInCellsX() - 1)
- {
- CellData data(costmap->getIndex(cell.x_+1, cell.y_),
- cell.x_+1, cell.y_, cell.src_x_, cell.src_y_);
- m[dist].push_back(data);
- }
- if (cell.y_ < costmap->getSizeInCellsY() - 1)
- {
- CellData data(costmap->getIndex(cell.x_, cell.y_+1),
- cell.x_, cell.y_+1, cell.src_x_, cell.src_y_);
- m[dist].push_back(data);
- }
- }
- }
- }
- delete[] seen;
- }
- TEST(costmap, testAdjacentToObstacleCanStillMove){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
- layers.resizeMap(10, 10, 1, 0, 0);
-
-
- std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
- addObservation(olayer, 0, 0, MAX_Z);
- layers.updateMap(0,0,0);
- Costmap2D* costmap = layers.getCostmap();
-
- EXPECT_EQ( LETHAL_OBSTACLE, costmap->getCost( 0, 0 ));
- EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 0 ));
- EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 2, 0 ));
- EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 3, 0 ));
- EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 2, 1 ));
- EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 1 ));
- }
- TEST(costmap, testInflationShouldNotCreateUnknowns){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
- layers.resizeMap(10, 10, 1, 0, 0);
-
-
- std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
- addObservation(olayer, 0, 0, MAX_Z);
- layers.updateMap(0,0,0);
- Costmap2D* costmap = layers.getCostmap();
- EXPECT_EQ( countValues(*costmap, NO_INFORMATION), 0 );
- }
- TEST(costmap, testCostFunctionCorrectness){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
- layers.resizeMap(100, 100, 1, 0, 0);
-
-
- std::vector<Point> polygon = setRadii(layers, 5.0, 6.25, 10.5);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
- addObservation(olayer, 50, 50, MAX_Z);
- layers.updateMap(0,0,0);
- Costmap2D* map = layers.getCostmap();
-
-
-
- for(unsigned int i = 0; i <= (unsigned int)ceil(5.0); i++){
-
- ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
- ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
-
- ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
- ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
-
- ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
- ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
-
- ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
- ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
- }
-
- for(unsigned int i = (unsigned int)(ceil(5.0) + 1); i <= (unsigned int)ceil(10.5); i++){
- unsigned char expectedValue = ilayer->computeCost(i/1.0);
- ASSERT_EQ(map->getCost(50 + i, 50), expectedValue);
- }
-
-
- }
- TEST(costmap, testInflationOrderCorrectness){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
- layers.resizeMap(10, 10, 1, 0, 0);
-
-
- const double inflation_radius = 4.1;
- std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, inflation_radius);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
-
-
- addObservation(olayer, 4, 4, MAX_Z);
- addObservation(olayer, 5, 5, MAX_Z);
- layers.updateMap(0, 0, 0);
- validatePointInflation(4, 4, layers.getCostmap(), ilayer, inflation_radius);
- validatePointInflation(5, 5, layers.getCostmap(), ilayer, inflation_radius);
- }
- TEST(costmap, testInflation){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
-
-
- std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
- addStaticLayer(layers, tf);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
- Costmap2D* costmap = layers.getCostmap();
- layers.updateMap(0,0,0);
-
- ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)20);
- ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)28);
-
- addObservation(olayer, 0, 0, 0.4);
- layers.updateMap(0,0,0);
-
- ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)51);
-
-
- addObservation(olayer, 2, 0);
- layers.updateMap(0,0,0);
-
-
-
- ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)54);
-
- addObservation(olayer, 1, 9);
- layers.updateMap(0,0,0);
- ASSERT_EQ(costmap->getCost(1, 9), LETHAL_OBSTACLE);
- ASSERT_EQ(costmap->getCost(0, 9), INSCRIBED_INFLATED_OBSTACLE);
- ASSERT_EQ(costmap->getCost(2, 9), INSCRIBED_INFLATED_OBSTACLE);
-
- addObservation(olayer, 0, 9);
- layers.updateMap(0,0,0);
- ASSERT_EQ(costmap->getCost(0, 9), LETHAL_OBSTACLE);
- }
- TEST(costmap, testInflation2){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
-
-
- std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
- addStaticLayer(layers, tf);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
-
- addObservation(olayer, 1, 1, MAX_Z);
- addObservation(olayer, 2, 1, MAX_Z);
- addObservation(olayer, 2, 2, MAX_Z);
- layers.updateMap(0,0,0);
- Costmap2D* costmap = layers.getCostmap();
-
- ASSERT_EQ(costmap->getCost(2, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
- ASSERT_EQ(costmap->getCost(3, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
- }
- TEST(costmap, testInflation3){
- tf2_ros::Buffer tf;
- LayeredCostmap layers("frame", false, false);
- layers.resizeMap(10, 10, 1, 0, 0);
-
- std::vector<Point> polygon = setRadii(layers, 1, 1.75, 3);
- ObstacleLayer* olayer = addObstacleLayer(layers, tf);
- InflationLayer* ilayer = addInflationLayer(layers, tf);
- layers.setFootprint(polygon);
-
- Costmap2D* costmap = layers.getCostmap();
- ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)0);
- ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)0);
- printMap(*costmap);
-
- addObservation(olayer, 5, 5, MAX_Z);
- layers.updateMap(0,0,0);
- printMap(*costmap);
-
- ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
- ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
- ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
-
- layers.updateMap(0,0,0);
- ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
- ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
- ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
- }
- int main(int argc, char** argv){
- ros::init(argc, argv, "inflation_tests");
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
- }
|