The CostmapWrapper class manages access to a costmap by locking/unlocking its mutex and handles (de)activation. More...
#include <costmap_wrapper.h>

| Public Types | |
| typedef boost::shared_ptr< CostmapWrapper > | Ptr | 
| Public Member Functions | |
| void | checkActivate () | 
| Check whether the costmap should be activated.  More... | |
| void | checkDeactivate () | 
| Check whether the costmap should and could be deactivated.  More... | |
| void | clear () | 
| Clear costmap.  More... | |
| CostmapWrapper (const std::string &name, const TFPtr &tf_listener_ptr) | |
| Constructor.  More... | |
| void | reconfigure (double shutdown_costmap, double shutdown_costmap_delay) | 
| Reconfiguration method called by dynamic reconfigure.  More... | |
| virtual | ~CostmapWrapper () | 
| Destructor.  More... | |
|  Public Member Functions inherited from costmap_2d::Costmap2DROS | |
| Costmap2DROS (std::string name, tf::TransformListener &tf) | |
| std::string | getBaseFrameID () | 
| Costmap2D * | getCostmap () | 
| std::string | getGlobalFrameID () | 
| LayeredCostmap * | getLayeredCostmap () | 
| void | getOrientedFootprint (std::vector< geometry_msgs::Point > &oriented_footprint) const | 
| std::vector< geometry_msgs::Point > | getRobotFootprint () | 
| geometry_msgs::Polygon | getRobotFootprintPolygon () | 
| bool | getRobotPose (tf::Stamped< tf::Pose > &global_pose) const | 
| std::vector< geometry_msgs::Point > | getUnpaddedRobotFootprint () | 
| bool | isCurrent () | 
| void | pause () | 
| void | resetLayers () | 
| void | resume () | 
| void | setUnpaddedRobotFootprint (const std::vector< geometry_msgs::Point > &points) | 
| void | setUnpaddedRobotFootprintPolygon (const geometry_msgs::Polygon &footprint) | 
| void | start () | 
| void | stop () | 
| void | updateMap () | 
| ~Costmap2DROS () | |
| Private Member Functions | |
| void | deactivate (const ros::TimerEvent &event) | 
| Timer-triggered deactivation of the costmap.  More... | |
| Private Attributes | |
| boost::mutex | check_costmap_mutex_ | 
| Start/stop costmap mutex; concurrent calls to start can lead to segfault.  More... | |
| bool | clear_on_shutdown_ | 
| clear the costmap, when shutting down  More... | |
| int16_t | costmap_users_ | 
| keep track of plugins using costmap  More... | |
| ros::NodeHandle | private_nh_ | 
| Private node handle.  More... | |
| bool | shutdown_costmap_ | 
| don't update costmap when not using it  More... | |
| ros::Duration | shutdown_costmap_delay_ | 
| costmap delayed shutdown delay  More... | |
| ros::Timer | shutdown_costmap_timer_ | 
| costmap delayed shutdown timer  More... | |
| Additional Inherited Members | |
|  Protected Attributes inherited from costmap_2d::Costmap2DROS | |
| std::string | global_frame_ | 
| LayeredCostmap * | layered_costmap_ | 
| std::string | name_ | 
| std::string | robot_base_frame_ | 
| tf::TransformListener & | tf_ | 
| double | transform_tolerance_ | 
The CostmapWrapper class manages access to a costmap by locking/unlocking its mutex and handles (de)activation.
Definition at line 63 of file costmap_wrapper.h.
Definition at line 66 of file costmap_wrapper.h.
| mbf_costmap_nav::CostmapWrapper::CostmapWrapper | ( | const std::string & | name, | 
| const TFPtr & | tf_listener_ptr | ||
| ) | 
Constructor.
| tf_listener_ptr | Shared pointer to a common TransformListener | 
Definition at line 48 of file costmap_wrapper.cpp.
| 
 | virtual | 
Destructor.
Definition at line 65 of file costmap_wrapper.cpp.
| void mbf_costmap_nav::CostmapWrapper::checkActivate | ( | ) | 
Check whether the costmap should be activated.
Definition at line 96 of file costmap_wrapper.cpp.
| void mbf_costmap_nav::CostmapWrapper::checkDeactivate | ( | ) | 
Check whether the costmap should and could be deactivated.
Definition at line 112 of file costmap_wrapper.cpp.
| void mbf_costmap_nav::CostmapWrapper::clear | ( | ) | 
Clear costmap.
Definition at line 89 of file costmap_wrapper.cpp.
| 
 | private | 
Timer-triggered deactivation of the costmap.
Definition at line 128 of file costmap_wrapper.cpp.
| void mbf_costmap_nav::CostmapWrapper::reconfigure | ( | double | shutdown_costmap, | 
| double | shutdown_costmap_delay | ||
| ) | 
Reconfiguration method called by dynamic reconfigure.
| shutdown_costmap | Determines whether or not to shutdown the costmap when move_base_flex is inactive. | 
| shutdown_costmap_delay | How long in seconds to wait after last action before shutting down the costmap. | 
Definition at line 71 of file costmap_wrapper.cpp.
| 
 | private | 
Start/stop costmap mutex; concurrent calls to start can lead to segfault.
Definition at line 110 of file costmap_wrapper.h.
| 
 | private | 
clear the costmap, when shutting down
Definition at line 112 of file costmap_wrapper.h.
| 
 | private | 
keep track of plugins using costmap
Definition at line 113 of file costmap_wrapper.h.
| 
 | private | 
Private node handle.
Definition at line 108 of file costmap_wrapper.h.
| 
 | private | 
don't update costmap when not using it
Definition at line 111 of file costmap_wrapper.h.
| 
 | private | 
costmap delayed shutdown delay
Definition at line 115 of file costmap_wrapper.h.
| 
 | private | 
costmap delayed shutdown timer
Definition at line 114 of file costmap_wrapper.h.