#include <costmap_2d/cost_values.h>
#include <costmap_2d/costmap_2d.h>
#include <costmap_2d/static_layer.h>
#include <costmap_2d/obstacle_layer.h>
#include <costmap_2d/inflation_layer.h>
#include <sensor_msgs/point_cloud2_iterator.h>
Go to the source code of this file.
Functions | |
costmap_2d::InflationLayer * | addInflationLayer (costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf) |
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) |
costmap_2d::ObstacleLayer * | addObstacleLayer (costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf) |
void | addStaticLayer (costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf) |
unsigned int | countValues (costmap_2d::Costmap2D &costmap, unsigned char value, bool equal=true) |
const double | MAX_Z (1.0) |
char | printableCost (unsigned char cost) |
void | printMap (costmap_2d::Costmap2D &costmap) |
costmap_2d::InflationLayer* addInflationLayer | ( | costmap_2d::LayeredCostmap & | layers, |
tf2_ros::Buffer & | tf | ||
) |
Definition at line 89 of file 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 |
||
) |
Definition at line 67 of file testing_helper.h.
costmap_2d::ObstacleLayer* addObstacleLayer | ( | costmap_2d::LayeredCostmap & | layers, |
tf2_ros::Buffer & | tf | ||
) |
Definition at line 59 of file testing_helper.h.
void addStaticLayer | ( | costmap_2d::LayeredCostmap & | layers, |
tf2_ros::Buffer & | tf | ||
) |
Definition at line 52 of file testing_helper.h.
unsigned int countValues | ( | costmap_2d::Costmap2D & | costmap, |
unsigned char | value, | ||
bool | equal = true |
||
) |
Definition at line 37 of file testing_helper.h.
const double MAX_Z | ( | 1. | 0 | ) |
char printableCost | ( | unsigned char | cost | ) |
Definition at line 14 of file testing_helper.h.
void printMap | ( | costmap_2d::Costmap2D & | costmap | ) |
Definition at line 26 of file testing_helper.h.