Public Member Functions | Static Public Attributes
nav_core2::Costmap Class Reference

#include <costmap.h>

Inheritance diagram for nav_core2::Costmap:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool canTrackChanges ()
 Flag to indicate whether this costmap is able to track how much has changed.
virtual UIntBounds getChangeBounds (const std::string &ns)
 If canTrackChanges, get the bounding box for how much of the costmap has changed.
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.
virtual void initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf)
 Initialization function for the Costmap.
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.
virtual ~Costmap ()
 Virtual Destructor.

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

Detailed Description

Definition at line 47 of file costmap.h.


Constructor & Destructor Documentation

virtual nav_core2::Costmap::~Costmap ( ) [inline, virtual]

Virtual Destructor.

Definition at line 60 of file costmap.h.


Member Function Documentation

virtual bool nav_core2::Costmap::canTrackChanges ( ) [inline, virtual]

Flag to indicate whether this costmap is able to track how much has changed.

Definition at line 112 of file costmap.h.

virtual UIntBounds nav_core2::Costmap::getChangeBounds ( const std::string &  ns) [inline, virtual]

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)

Parameters:
nsThe namespace
Returns:
Updated bounds
Exceptions:
std::runtime_errorIf canTrackChanges is false, the returned bounds would be meaningless

Definition at line 137 of file costmap.h.

unsigned char nav_core2::Costmap::getCost ( const unsigned int  x,
const unsigned int  y 
) [inline]

Definition at line 74 of file costmap.h.

unsigned char nav_core2::Costmap::getCost ( const nav_grid::Index &  index) [inline]

Definition at line 79 of file costmap.h.

virtual mutex_t* nav_core2::Costmap::getMutex ( ) [pure virtual]

Accessor for boost mutex.

Implemented in nav_core2::BasicCostmap.

virtual void nav_core2::Costmap::initialize ( const ros::NodeHandle parent,
const std::string &  name,
TFListenerPtr  tf 
) [inline, virtual]

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.

Parameters:
parentNodeHandle to derive other NodeHandles from
nameThe namespace for the costmap
tfA pointer to a transform listener

Definition at line 72 of file costmap.h.

void nav_core2::Costmap::setCost ( const unsigned int  x,
const unsigned int  y,
const unsigned char  cost 
) [inline]

Definition at line 84 of file costmap.h.

void nav_core2::Costmap::setCost ( const nav_grid::Index &  index,
const unsigned char  cost 
) [inline]

Definition at line 89 of file costmap.h.

virtual void nav_core2::Costmap::update ( ) [inline, virtual]

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.

Definition at line 101 of file costmap.h.


Member Data Documentation

const unsigned char nav_core2::Costmap::FREE_SPACE = 0 [static]

Definition at line 53 of file costmap.h.

const unsigned char nav_core2::Costmap::INSCRIBED_INFLATED_OBSTACLE = 253 [static]

Definition at line 52 of file costmap.h.

const unsigned char nav_core2::Costmap::LETHAL_OBSTACLE = 254 [static]

Definition at line 51 of file costmap.h.

const unsigned char nav_core2::Costmap::NO_INFORMATION = 255 [static]

Definition at line 50 of file costmap.h.


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


nav_core2
Author(s):
autogenerated on Wed Jun 26 2019 20:09:31