testing_helper.h
Go to the documentation of this file.
1 #ifndef COSTMAP_2D_TESTING_HELPER_H
2 #define COSTMAP_2D_TESTING_HELPER_H
3 
9 
11 
12 const double MAX_Z(1.0);
13 
14 void setValues(costmap_2d::Costmap2D& costmap, const unsigned char* map)
15 {
16  int index = 0;
17  for (int i = 0; i < costmap.getSizeInCellsY(); i++){
18  for (int j = 0; j < costmap.getSizeInCellsX(); j++){
19  costmap.setCost(j, i, map[index]);
20  }
21  }
22 }
23 
24 char printableCost(unsigned char cost)
25 {
26  switch (cost)
27  {
28  case costmap_2d::NO_INFORMATION: return '?';
29  case costmap_2d::LETHAL_OBSTACLE: return 'L';
31  case costmap_2d::FREE_SPACE: return '.';
32  default: return '0' + (unsigned char) (10 * cost / 255);
33  }
34 }
35 
37 {
38  printf("map:\n");
39  for (int i = 0; i < costmap.getSizeInCellsY(); i++){
40  for (int j = 0; j < costmap.getSizeInCellsX(); j++){
41  printf("%4d", int(costmap.getCost(j, i)));
42  }
43  printf("\n\n");
44  }
45 }
46 
47 unsigned int countValues(costmap_2d::Costmap2D& costmap, unsigned char value, bool equal = true)
48 {
49  unsigned int count = 0;
50  for (int i = 0; i < costmap.getSizeInCellsY(); i++){
51  for (int j = 0; j < costmap.getSizeInCellsX(); j++){
52  unsigned char c = costmap.getCost(j, i);
53  if ((equal && c == value) || (!equal && c != value))
54  {
55  count+=1;
56  }
57  }
58  }
59  return count;
60 }
61 
63 {
66  slayer->initialize(&layers, "static", &tf);
67 }
68 
70 {
72  olayer->initialize(&layers, "obstacles", &tf);
74  return olayer;
75 }
76 
77 void addObservation(costmap_2d::ObstacleLayer* olayer, double x, double y, double z = 0.0,
78  double ox = 0.0, double oy = 0.0, double oz = MAX_Z){
79  sensor_msgs::PointCloud2 cloud;
80  sensor_msgs::PointCloud2Modifier modifier(cloud);
81  modifier.setPointCloud2FieldsByString(1, "xyz");
82  modifier.resize(1);
83  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
84  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
85  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
86  *iter_x = x;
87  *iter_y = y;
88  *iter_z = z;
89 
90  geometry_msgs::Point p;
91  p.x = ox;
92  p.y = oy;
93  p.z = oz;
94 
95  costmap_2d::Observation obs(p, cloud, 100.0, 100.0); // obstacle range = raytrace range = 100.0
96  olayer->addStaticObservation(obs, true, true);
97 }
98 
100 {
102  ilayer->initialize(&layers, "inflation", &tf);
103  boost::shared_ptr<costmap_2d::Layer> ipointer(ilayer);
104  layers.addPlugin(ipointer);
105  return ilayer;
106 }
107 
108 
109 #endif // COSTMAP_2D_TESTING_HELPER_H
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:197
unsigned int countValues(costmap_2d::Costmap2D &costmap, unsigned char value, bool equal=true)
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:430
const double MAX_Z(1.0)
costmap_2d::InflationLayer * addInflationLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:435
costmap_2d::ObstacleLayer * addObstacleLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
char printableCost(unsigned char cost)
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.h:46
void initialize(LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf)
Definition: layer.cpp:43
static const unsigned char FREE_SPACE
Definition: cost_values.h:45
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
Definition: cost_values.h:44
void addPlugin(boost::shared_ptr< Layer > plugin)
void setValues(costmap_2d::Costmap2D &costmap, const unsigned char *map)
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:43
static const unsigned char NO_INFORMATION
Definition: cost_values.h:42
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)
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:60
void printMap(costmap_2d::Costmap2D &costmap)
Instantiates different layer plugins and aggregates them into one score.
void setPointCloud2FieldsByString(int n_fields,...)
void addStaticLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:192


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:03