2 #include <gtest/gtest.h> 20 clr.
setParam(
"reset_distance", distance);
22 std::vector<std::string> clearable_layers;
24 clearable_layers.push_back( std::string(
"obstacles") );
26 clearable_layers.push_back( std::string(
"static_map") );
28 clr.
setParam(
"layer_names", clearable_layers);
30 clear.
initialize(name, transformer, global_costmap, local_costmap);
35 void testCountLethal(std::string name,
double distance,
bool obstacles,
bool static_map,
int global_lethal,
int local_lethal=0)
44 if(plugin->getName().find(
"obstacles")!=std::string::npos){
47 addObservation(&(*olayer), 0.0, 5.0,
MAX_Z/2, 0, 0,
MAX_Z/2);
53 olayer->clearStaticObservations(
true,
true);
66 TEST(ClearTester, basicTest){
70 TEST(ClearTester, bigRadiusTest){
74 TEST(ClearTester, clearNoLayersTest){
78 TEST(ClearTester, clearBothTest){
82 TEST(ClearTester, clearBothTest2){
87 int main(
int argc,
char** argv){
89 testing::InitGoogleTest(&argc, argv);
91 return RUN_ALL_TESTS();
unsigned int countValues(costmap_2d::Costmap2D &costmap, unsigned char value, bool equal=true)
tf::TransformListener * transformer
void testCountLethal(std::string name, double distance, bool obstacles, bool static_map, int global_lethal, int local_lethal=0)
void testClearBehavior(std::string name, double distance, bool obstacles, bool static_map, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< boost::shared_ptr< Layer > > * getPlugins()
A recovery behavior that reverts the navigation stack's costmaps to the static map outside of a user-...
int main(int argc, char **argv)
void runBehavior()
Run the ClearCostmapRecovery recovery behavior. Reverts the costmap to the static map outside of a us...
static const unsigned char LETHAL_OBSTACLE
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 initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the ClearCostmapRecovery recovery behavior.
void printMap(costmap_2d::Costmap2D &costmap)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
LayeredCostmap * getLayeredCostmap()
TEST(ClearTester, basicTest)