Public Types | Public Member Functions | Static Public Attributes | List of all members
nav_core2::Costmap Class Referenceabstract

#include <costmap.h>

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

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_tgetMutex ()=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
 
getValue (const Index &index)
 
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{})
 
operator() (const Index &index) const
 
operator() (const unsigned int x, const unsigned int y) const
 
operator() (const Index &index) const
 
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 >
default_value_
 
NavGridInfo info_
 

Detailed Description

Definition at line 48 of file costmap.h.

Member Typedef Documentation

using nav_core2::Costmap::mutex_t = boost::recursive_mutex

Definition at line 104 of file costmap.h.

using nav_core2::Costmap::Ptr = std::shared_ptr<Costmap>

Definition at line 56 of file costmap.h.

Constructor & Destructor Documentation

virtual nav_core2::Costmap::~Costmap ( )
inlinevirtual

Virtual Destructor.

Definition at line 61 of file costmap.h.

Member Function Documentation

virtual bool nav_core2::Costmap::canTrackChanges ( )
inlinevirtual

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

Definition at line 113 of file costmap.h.

virtual UIntBounds nav_core2::Costmap::getChangeBounds ( const std::string &  ns)
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)

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

Definition at line 138 of file costmap.h.

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

Definition at line 75 of file costmap.h.

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

Definition at line 80 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 
)
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.

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

Definition at line 73 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 85 of file costmap.h.

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

Definition at line 90 of file costmap.h.

virtual void nav_core2::Costmap::update ( )
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.

Definition at line 102 of file costmap.h.

Member Data Documentation

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

Definition at line 54 of file costmap.h.

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

Definition at line 53 of file costmap.h.

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

Definition at line 52 of file costmap.h.

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

Definition at line 51 of file costmap.h.


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


nav_core2
Author(s):
autogenerated on Sun Jan 10 2021 04:08:27