Go to the documentation of this file.
35 #ifndef NAV_CORE2_COSTMAP_H
36 #define NAV_CORE2_COSTMAP_H
41 #include <boost/thread.hpp>
56 using Ptr = std::shared_ptr<Costmap>;
75 inline unsigned char getCost(
const unsigned int x,
const unsigned int y)
85 inline void setCost(
const unsigned int x,
const unsigned int y,
const unsigned char cost)
142 throw std::runtime_error(
"You called 'getChangeBounds()' on a derived Costmap type that is not capable of "
143 "tracking changes (i.e. canTrackChanges() returns false). You shouldn't do that.");
147 throw std::runtime_error(
"You called 'getChangeBounds()' on a derived Costmap type that is capable of tracking "
148 "changes but has not properly implemented this function. You should yell at the author "
149 "of the derived Costmap.");
156 #endif // NAV_CORE2_COSTMAP_H
virtual void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf)
Initialization function for the Costmap.
static const unsigned char NO_INFORMATION
virtual void setValue(const unsigned int x, const unsigned int y, const T &value)=0
static const unsigned char FREE_SPACE
boost::recursive_mutex mutex_t
unsigned char getCost(const unsigned int x, const unsigned int y)
virtual ~Costmap()
Virtual Destructor.
unsigned char getCost(const nav_grid::Index &index)
void setCost(const nav_grid::Index &index, const unsigned char cost)
virtual UIntBounds getChangeBounds(const std::string &ns)
If canTrackChanges, get the bounding box for how much of the costmap has changed.
static const unsigned char LETHAL_OBSTACLE
virtual void update()
Update the values in the costmap.
std::shared_ptr< Costmap > Ptr
void setCost(const unsigned int x, const unsigned int y, const unsigned char cost)
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
virtual mutex_t * getMutex()=0
Accessor for boost mutex.
virtual bool canTrackChanges()
Flag to indicate whether this costmap is able to track how much has changed.
virtual T getValue(const unsigned int x, const unsigned int y) const =0
nav_core2
Author(s):
autogenerated on Sun May 18 2025 02:47:17