Go to the documentation of this file.
43 #include <gtest/gtest.h>
46 using geometry_msgs::Point;
50 std::vector<Point> polygon;
67 nh.
setParam(
"/inflation_tests/inflation/inflation_radius", inflation_radius);
77 std::map<double, std::vector<CellData> > m;
79 m[0].push_back(initial);
80 for (std::map<
double, std::vector<CellData> >::iterator bin = m.begin(); bin != m.end(); ++bin)
82 for (
int i = 0; i < bin->second.size(); ++i)
84 const CellData& cell = bin->second[i];
90 double dist = hypot(dx, dy);
92 unsigned char expected_cost = ilayer->
computeCost(dist);
93 ASSERT_TRUE(costmap->
getCost(cell.
x_, cell.
y_) >= expected_cost);
95 if (dist > inflation_radius)
100 if (dist == bin->first)
111 m[dist].push_back(data);
117 m[dist].push_back(data);
123 m[dist].push_back(data);
129 m[dist].push_back(data);
137 TEST(costmap, testAdjacentToObstacleCanStillMove){
144 std::vector<Point> polygon =
setRadii(layers, 2.1, 2.3, 4.1);
163 TEST(costmap, testInflationShouldNotCreateUnknowns){
170 std::vector<Point> polygon =
setRadii(layers, 2.1, 2.3, 4.1);
188 TEST(costmap, testCostFunctionCorrectness){
195 std::vector<Point> polygon =
setRadii(layers, 5.0, 6.25, 10.5);
210 for(
unsigned int i = 0; i <= (
unsigned int)ceil(5.0); i++){
226 for(
unsigned int i = (
unsigned int)(ceil(5.0) + 1); i <= (
unsigned int)ceil(10.5); i++){
227 unsigned char expectedValue = ilayer->
computeCost(i/1.0);
228 ASSERT_EQ(map->
getCost(50 + i, 50), expectedValue);
256 TEST(costmap, testInflationOrderCorrectness){
263 const double inflation_radius = 4.1;
264 std::vector<Point> polygon =
setRadii(layers, 2.1, 2.3, inflation_radius);
291 std::vector<Point> polygon =
setRadii(layers, 1, 1, 1);
355 std::vector<Point> polygon =
setRadii(layers, 1, 1, 1);
383 std::vector<Point> polygon =
setRadii(layers, 1, 1.75, 3);
413 int main(
int argc,
char** argv){
414 ros::init(argc, argv,
"inflation_tests");
415 testing::InitGoogleTest(&argc, argv);
416 return RUN_ALL_TESTS();
void setParam(const std::string &key, bool b) const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void addObservation(costmap_2d::ObstacleLayer *olayer, double x, double y, double z=0.0, double ox=0.0, double oy=0.0, double oz=MAX_Z)
void addStaticLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
static const unsigned char NO_INFORMATION
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Storage for cell information used during obstacle inflation.
virtual unsigned char computeCost(double distance) const
Given a distance, compute a cost.
A 2D costmap provides a mapping between points in the world and their associated "costs".
costmap_2d::ObstacleLayer * addObstacleLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
std::vector< Point > setRadii(LayeredCostmap &layers, double length, double width, double inflation_radius)
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
static const unsigned char LETHAL_OBSTACLE
int main(int argc, char **argv)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
Instantiates different layer plugins and aggregates them into one score.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
static const unsigned char FREE_SPACE
costmap_2d::InflationLayer * addInflationLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
TEST(costmap, testAdjacentToObstacleCanStillMove)
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
void printMap(costmap_2d::Costmap2D &costmap)
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
unsigned int countValues(costmap_2d::Costmap2D &costmap, unsigned char value, bool equal=true)
void validatePointInflation(unsigned int mx, unsigned int my, Costmap2D *costmap, InflationLayer *ilayer, double inflation_radius)
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17