#include <costmap.h>
Public Types | |
using | mutex_t = boost::recursive_mutex |
using | Ptr = std::shared_ptr< Costmap > |
Public Member Functions | |
virtual bool | canTrackChanges () |
Flag to indicate whether this costmap is able to track how much has changed. More... | |
virtual UIntBounds | getChangeBounds (const std::string &ns) |
If canTrackChanges, get the bounding box for how much of the costmap has changed. More... | |
unsigned char | getCost (const unsigned int x, const unsigned int y) |
unsigned char | getCost (const nav_grid::Index &index) |
virtual mutex_t * | getMutex ()=0 |
Accessor for boost mutex. More... | |
virtual void | initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf) |
Initialization function for the Costmap. More... | |
void | setCost (const unsigned int x, const unsigned int y, const unsigned char cost) |
void | setCost (const nav_grid::Index &index, const unsigned char cost) |
virtual void | update () |
Update the values in the costmap. More... | |
virtual | ~Costmap () |
Virtual Destructor. More... | |
Public Member Functions inherited from nav_grid::NavGrid< unsigned char > | |
std::string | getFrameId () const |
unsigned int | getHeight () const |
NavGridInfo | getInfo () const |
double | getOriginX () const |
double | getOriginY () const |
double | getResolution () const |
T | getValue (const Index &index) |
T | getValue (const Index &index) |
virtual T | getValue (const unsigned int x, const unsigned int y) const =0 |
unsigned int | getWidth () const |
NavGrid (const T default_value=T{}) | |
T | operator() (const Index &index) const |
T | operator() (const unsigned int x, const unsigned int y) const |
T | operator() (const Index &index) const |
T | operator() (const unsigned int x, const unsigned int y) const |
virtual void | reset ()=0 |
void | setDefaultValue (const T new_value) |
virtual void | setInfo (const NavGridInfo &new_info)=0 |
void | setValue (const Index &index, const T &value) |
void | setValue (const Index &index, const T &value) |
virtual void | setValue (const unsigned int x, const unsigned int y, const T &value)=0 |
virtual void | updateInfo (const NavGridInfo &new_info) |
Static Public Attributes | |
static const unsigned char | FREE_SPACE = 0 |
static const unsigned char | INSCRIBED_INFLATED_OBSTACLE = 253 |
static const unsigned char | LETHAL_OBSTACLE = 254 |
static const unsigned char | NO_INFORMATION = 255 |
Additional Inherited Members | |
Protected Attributes inherited from nav_grid::NavGrid< unsigned char > | |
T | default_value_ |
NavGridInfo | info_ |
using nav_core2::Costmap::mutex_t = boost::recursive_mutex |
using nav_core2::Costmap::Ptr = std::shared_ptr<Costmap> |
|
inlinevirtual |
|
inlinevirtual |
|
inlinevirtual |
If canTrackChanges, get the bounding box for how much of the costmap has changed.
Rather than querying based on time stamps (which can require an arbitrary amount of storage) we instead query based on a namespace. The return bounding box reports how much of the costmap has changed since the last time this method was called with a particular namespace. If a namespace is new, then it returns a bounding box for the whole costmap. The max values are inclusive.
Example Sequence with a 5x5 costmap: (results listed (min_x,min_y):(max_x, max_y)) 0) getChangeBounds("A") –> (0,0):(4,4) 1) getChangeBounds("B") –> (0,0):(4,4) 2) update cell 1, 1 3) getChangeBounds("C") –> (0,0):(4,4) 4) getChangeBounds("A") –> (1,1):(1,1) 5) getChangeBounds("A") –> (empty bounds) (i.e. nothing was updated since last call) 6) updateCell 2, 4 7) getChangeBounds("A") –> (2,4):(2,4) 8) getChangeBounds("B") –> (1,1):(2,4)
ns | The namespace |
std::runtime_error | If canTrackChanges is false, the returned bounds would be meaningless |
|
inline |
|
inline |
|
pure virtual |
Accessor for boost mutex.
Implemented in nav_core2::BasicCostmap.
|
inlinevirtual |
Initialization function for the Costmap.
ROS parameters/topics are expected to be in the parent/name namespace. It is suggested that all NodeHandles in the costmap use the parent NodeHandle's callback queue.
parent | NodeHandle to derive other NodeHandles from |
name | The namespace for the costmap |
tf | A pointer to a transform listener |
|
inline |
|
inline |
|
inlinevirtual |
Update the values in the costmap.
Note that this method can throw CostmapExceptions to indicate problems, like when it would be unsafe to navigate. e.g. If the costmap expects laser data at a given rate, but laser data hasn't shown up in a while, this method might throw a CostmapDataLagException.
|
static |
|
static |
|
static |
|
static |