Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_costmap_nav::CostmapWrapper Class Reference

The CostmapWrapper class manages access to a costmap by locking/unlocking its mutex and handles (de)activation. More...

#include <costmap_wrapper.h>

Inheritance diagram for mbf_costmap_nav::CostmapWrapper:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< CostmapWrapperPtr
 

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 (const std::string &name, tf2_ros::Buffer &tf)
 
std::string getBaseFrameID ()
 
Costmap2DgetCostmap ()
 
std::string getGlobalFrameID ()
 
LayeredCostmapgetLayeredCostmap ()
 
std::string getName () const
 
void getOrientedFootprint (std::vector< geometry_msgs::Point > &oriented_footprint) const
 
std::vector< geometry_msgs::PointgetRobotFootprint ()
 
geometry_msgs::Polygon getRobotFootprintPolygon ()
 
bool getRobotPose (geometry_msgs::PoseStamped &global_pose) const
 
double getTransformTolerance () const
 
std::vector< geometry_msgs::PointgetUnpaddedRobotFootprint ()
 
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_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
std::string robot_base_frame_
 
tf2_ros::Buffertf_
 
double transform_tolerance_
 

Detailed Description

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.

Member Typedef Documentation

◆ Ptr

Definition at line 66 of file costmap_wrapper.h.

Constructor & Destructor Documentation

◆ CostmapWrapper()

mbf_costmap_nav::CostmapWrapper::CostmapWrapper ( const std::string &  name,
const TFPtr tf_listener_ptr 
)

Constructor.

Parameters
tf_listener_ptrShared pointer to a common TransformListener

Definition at line 48 of file costmap_wrapper.cpp.

◆ ~CostmapWrapper()

mbf_costmap_nav::CostmapWrapper::~CostmapWrapper ( )
virtual

Destructor.

Definition at line 65 of file costmap_wrapper.cpp.

Member Function Documentation

◆ checkActivate()

void mbf_costmap_nav::CostmapWrapper::checkActivate ( )

Check whether the costmap should be activated.

Definition at line 96 of file costmap_wrapper.cpp.

◆ checkDeactivate()

void mbf_costmap_nav::CostmapWrapper::checkDeactivate ( )

Check whether the costmap should and could be deactivated.

Definition at line 112 of file costmap_wrapper.cpp.

◆ clear()

void mbf_costmap_nav::CostmapWrapper::clear ( )

Clear costmap.

Definition at line 89 of file costmap_wrapper.cpp.

◆ deactivate()

void mbf_costmap_nav::CostmapWrapper::deactivate ( const ros::TimerEvent event)
private

Timer-triggered deactivation of the costmap.

Definition at line 128 of file costmap_wrapper.cpp.

◆ reconfigure()

void mbf_costmap_nav::CostmapWrapper::reconfigure ( double  shutdown_costmap,
double  shutdown_costmap_delay 
)

Reconfiguration method called by dynamic reconfigure.

Parameters
shutdown_costmapDetermines whether or not to shutdown the costmap when move_base_flex is inactive.
shutdown_costmap_delayHow long in seconds to wait after last action before shutting down the costmap.

Definition at line 71 of file costmap_wrapper.cpp.

Member Data Documentation

◆ check_costmap_mutex_

boost::mutex mbf_costmap_nav::CostmapWrapper::check_costmap_mutex_
private

Start/stop costmap mutex; concurrent calls to start can lead to segfault.

Definition at line 110 of file costmap_wrapper.h.

◆ clear_on_shutdown_

bool mbf_costmap_nav::CostmapWrapper::clear_on_shutdown_
private

clear the costmap, when shutting down

Definition at line 112 of file costmap_wrapper.h.

◆ costmap_users_

int16_t mbf_costmap_nav::CostmapWrapper::costmap_users_
private

keep track of plugins using costmap

Definition at line 113 of file costmap_wrapper.h.

◆ private_nh_

ros::NodeHandle mbf_costmap_nav::CostmapWrapper::private_nh_
private

Private node handle.

Definition at line 108 of file costmap_wrapper.h.

◆ shutdown_costmap_

bool mbf_costmap_nav::CostmapWrapper::shutdown_costmap_
private

don't update costmap when not using it

Definition at line 111 of file costmap_wrapper.h.

◆ shutdown_costmap_delay_

ros::Duration mbf_costmap_nav::CostmapWrapper::shutdown_costmap_delay_
private

costmap delayed shutdown delay

Definition at line 115 of file costmap_wrapper.h.

◆ shutdown_costmap_timer_

ros::Timer mbf_costmap_nav::CostmapWrapper::shutdown_costmap_timer_
private

costmap delayed shutdown timer

Definition at line 114 of file costmap_wrapper.h.


The documentation for this class was generated from the following files:


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Mon Feb 28 2022 22:49:55