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


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17