Go to the documentation of this file.
41 #ifndef MBF_COSTMAP_NAV__COSTMAP_WRAPPER_H_
42 #define MBF_COSTMAP_NAV__COSTMAP_WRAPPER_H_
84 void reconfigure(
double shutdown_costmap,
double shutdown_costmap_delay);
ros::NodeHandle private_nh_
Private node handle.
bool shutdown_costmap_
don't update costmap when not using it
bool clear_on_shutdown_
clear the costmap, when shutting down
void reconfigure(double shutdown_costmap, double shutdown_costmap_delay)
Reconfiguration method called by dynamic reconfigure.
void clear()
Clear costmap.
ros::Duration shutdown_costmap_delay_
costmap delayed shutdown delay
void checkActivate()
Check whether the costmap should be activated.
boost::mutex check_costmap_mutex_
Start/stop costmap mutex; concurrent calls to start can lead to segfault.
void deactivate(const ros::TimerEvent &event)
Timer-triggered deactivation of the costmap.
void checkDeactivate()
Check whether the costmap should and could be deactivated.
ros::Timer shutdown_costmap_timer_
costmap delayed shutdown timer
boost::shared_ptr< CostmapWrapper > Ptr
virtual ~CostmapWrapper()
Destructor.
The CostmapWrapper class manages access to a costmap by locking/unlocking its mutex and handles (de)a...
int16_t costmap_users_
keep track of plugins using costmap
CostmapWrapper(const std::string &name, const TFPtr &tf_listener_ptr)
Constructor.
mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:55