Go to the documentation of this file.
49 costmap_2d::Costmap2DROS(name, *tf_listener_ptr),
50 shutdown_costmap_(false), costmap_users_(0), private_nh_(
"~")
75 ROS_WARN(
"Zero shutdown costmaps delay is not recommended, as it forces us to enable costmaps on each action");
92 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*
getCostmap()->getMutex());
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
#define ROS_DEBUG_STREAM(args)
void checkActivate()
Check whether the costmap should be activated.
void deactivate(const ros::TimerEvent &event)
Timer-triggered deactivation of the costmap.
boost::mutex check_costmap_mutex_
Start/stop costmap mutex; concurrent calls to start can lead to segfault.
void checkDeactivate()
Check whether the costmap should and could be deactivated.
#define ROS_ASSERT_MSG(cond,...)
ros::Timer shutdown_costmap_timer_
costmap delayed shutdown timer
T param(const std::string ¶m_name, const T &default_val) const
virtual ~CostmapWrapper()
Destructor.
Costmap2D * getCostmap() const
int16_t costmap_users_
keep track of plugins using costmap
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
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