35 #ifndef NAV_CORE2_COSTMAP_H 36 #define NAV_CORE2_COSTMAP_H 41 #include <boost/thread.hpp> 55 using Ptr = std::shared_ptr<Costmap>;
74 inline unsigned char getCost(
const unsigned int x,
const unsigned int y)
84 inline void setCost(
const unsigned int x,
const unsigned int y,
const unsigned char cost)
141 throw std::runtime_error(
"You called 'getChangeBounds()' on a derived Costmap type that is not capable of " 142 "tracking changes (i.e. canTrackChanges() returns false). You shouldn't do that.");
146 throw std::runtime_error(
"You called 'getChangeBounds()' on a derived Costmap type that is capable of tracking " 147 "changes but has not properly implemented this function. You should yell at the author " 148 "of the derived Costmap.");
155 #endif // NAV_CORE2_COSTMAP_H
virtual void setValue(const unsigned int x, const unsigned int y, const T &value)=0
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
void setCost(const nav_grid::Index &index, const unsigned char cost)
void setCost(const unsigned int x, const unsigned int y, const unsigned char cost)
virtual T getValue(const unsigned int x, const unsigned int y) const =0
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 NO_INFORMATION
unsigned char getCost(const unsigned int x, const unsigned int y)
unsigned char getCost(const nav_grid::Index &index)
boost::recursive_mutex mutex_t
virtual bool canTrackChanges()
Flag to indicate whether this costmap is able to track how much has changed.
virtual void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf)
Initialization function for the Costmap.
std::shared_ptr< Costmap > Ptr
static const unsigned char LETHAL_OBSTACLE
std::shared_ptr< tf::TransformListener > TFListenerPtr
static const unsigned char FREE_SPACE
virtual void update()
Update the values in the costmap.
virtual mutex_t * getMutex()=0
Accessor for boost mutex.
virtual ~Costmap()
Virtual Destructor.