clear_costmap_recovery.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef CLEAR_COSTMAP_RECOVERY_H_
38 #define CLEAR_COSTMAP_RECOVERY_H_
41 #include <ros/ros.h>
43 
50  public:
57 
64  void initialize(std::string name, tf2_ros::Buffer* tf,
65  costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap);
66 
72  void runBehavior();
73 
74  private:
75  void clear(costmap_2d::Costmap2DROS* costmap);
76  void clearMap(boost::shared_ptr<costmap_2d::CostmapLayer> costmap, double pose_x, double pose_y);
78  std::string name_;
80  bool initialized_;
81  bool force_updating_;
82  double reset_distance_;
84  std::string affected_maps_;
85  std::set<std::string> clearable_layers_;
86  };
87 };
88 #endif
clear_costmap_recovery::ClearCostmapRecovery::clearMap
void clearMap(boost::shared_ptr< costmap_2d::CostmapLayer > costmap, double pose_x, double pose_y)
Definition: clear_costmap_recovery.cpp:168
clear_costmap_recovery::ClearCostmapRecovery::invert_area_to_clear_
bool invert_area_to_clear_
Definition: clear_costmap_recovery.h:118
boost::shared_ptr
clear_costmap_recovery::ClearCostmapRecovery::clearable_layers_
std::set< std::string > clearable_layers_
Layer names which will be cleared.
Definition: clear_costmap_recovery.h:120
ros.h
clear_costmap_recovery
Definition: clear_costmap_recovery.h:44
clear_costmap_recovery::ClearCostmapRecovery::force_updating_
bool force_updating_
force costmap update after clearing, so we don't need to wait for update thread
Definition: clear_costmap_recovery.h:116
clear_costmap_recovery::ClearCostmapRecovery::initialized_
bool initialized_
Definition: clear_costmap_recovery.h:115
clear_costmap_recovery::ClearCostmapRecovery::local_costmap_
costmap_2d::Costmap2DROS * local_costmap_
Definition: clear_costmap_recovery.h:112
clear_costmap_recovery::ClearCostmapRecovery::runBehavior
void runBehavior()
Run the ClearCostmapRecovery recovery behavior. Reverts the costmap to the static map outside of a us...
Definition: clear_costmap_recovery.cpp:89
costmap_2d_ros.h
clear_costmap_recovery::ClearCostmapRecovery::ClearCostmapRecovery
ClearCostmapRecovery()
Constructor, make sure to call initialize in addition to actually initialize the object.
Definition: clear_costmap_recovery.cpp:48
costmap_layer.h
clear_costmap_recovery::ClearCostmapRecovery
A recovery behavior that reverts the navigation stack's costmaps to the static map outside of a user-...
Definition: clear_costmap_recovery.h:84
recovery_behavior.h
tf2_ros::Buffer
clear_costmap_recovery::ClearCostmapRecovery::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the ClearCostmapRecovery recovery behavior.
Definition: clear_costmap_recovery.cpp:51
clear_costmap_recovery::ClearCostmapRecovery::name_
std::string name_
Definition: clear_costmap_recovery.h:113
tf
clear_costmap_recovery::ClearCostmapRecovery::global_costmap_
costmap_2d::Costmap2DROS * global_costmap_
Definition: clear_costmap_recovery.h:112
clear_costmap_recovery::ClearCostmapRecovery::tf_
tf2_ros::Buffer * tf_
Definition: clear_costmap_recovery.h:114
clear_costmap_recovery::ClearCostmapRecovery::clear
void clear(costmap_2d::Costmap2DROS *costmap)
Definition: clear_costmap_recovery.cpp:131
clear_costmap_recovery::ClearCostmapRecovery::affected_maps_
std::string affected_maps_
clear only local, global or both costmaps
Definition: clear_costmap_recovery.h:119
clear_costmap_recovery::ClearCostmapRecovery::reset_distance_
double reset_distance_
Definition: clear_costmap_recovery.h:117
costmap_2d::Costmap2DROS
nav_core::RecoveryBehavior


clear_costmap_recovery
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:30