Go to the documentation of this file. 1 #ifndef COSTMAP_2D_TESTING_HELPER_H
2 #define COSTMAP_2D_TESTING_HELPER_H
10 #include <sensor_msgs/point_cloud2_iterator.h>
12 const double MAX_Z(1.0);
22 default:
return '0' + (
unsigned char) (10 * cost / 255);
31 printf(
"%4d",
int(costmap.
getCost(j, i)));
39 unsigned int count = 0;
42 unsigned char c = costmap.
getCost(j, i);
43 if ((equal && c == value) || (!equal && c != value))
55 layers.
addPlugin(boost::shared_ptr<costmap_2d::Layer>(slayer));
63 layers.
addPlugin(boost::shared_ptr<costmap_2d::Layer>(olayer));
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");
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");
80 geometry_msgs::Point p;
93 boost::shared_ptr<costmap_2d::Layer> ipointer(ilayer);
99 #endif // COSTMAP_2D_TESTING_HELPER_H
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
static const unsigned char NO_INFORMATION
void initialize(LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf)
A 2D costmap provides a mapping between points in the world and their associated "costs".
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
costmap_2d::ObstacleLayer * addObstacleLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
static const unsigned char LETHAL_OBSTACLE
void addPlugin(boost::shared_ptr< Layer > plugin)
char printableCost(unsigned char cost)
Stores an observation in terms of a point cloud and the origin of the source.
Instantiates different layer plugins and aggregates them into one score.
static const unsigned char FREE_SPACE
costmap_2d::InflationLayer * addInflationLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
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)