Public Member Functions | Protected Attributes | List of all members
global_planner_tests::EasyCostmap Class Reference

An instantiation of the Costmap class that simply populates the grid from an image. More...

#include <easy_costmap.h>

Inheritance diagram for global_planner_tests::EasyCostmap:
Inheritance graph
[legend]

Public Member Functions

 EasyCostmap (const std::string &filename, const double resolution=0.1, const bool origin_at_center=false)
 Constructor, loads directly from an image filename. More...
 
 EasyCostmap ()
 Empty constructor. You need to call loadMapFromFile afterward. More...
 
void loadMapFromFile (const std::string &filename, const double resolution=0.1, const bool origin_at_center=false)
 
void reset () override
 
- Public Member Functions inherited from nav_core2::BasicCostmap
unsigned int getIndex (const unsigned int x, const unsigned int y) const
 
mutex_tgetMutex () override
 
unsigned char getValue (const unsigned int x, const unsigned int y) const override
 
void reset () override
 
void setInfo (const nav_grid::NavGridInfo &new_info) override
 
void setValue (const unsigned int x, const unsigned int y, const unsigned char &value) override
 
- Public Member Functions inherited from nav_core2::Costmap
virtual bool canTrackChanges ()
 
virtual UIntBounds getChangeBounds (const std::string &ns)
 
unsigned char getCost (const nav_grid::Index &index)
 
unsigned char getCost (const unsigned int x, const unsigned int y)
 
virtual void initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf)
 
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 ()
 
virtual ~Costmap ()
 

Protected Attributes

nav_msgs::OccupancyGrid original_grid_
 
- Protected Attributes inherited from nav_core2::BasicCostmap
std::vector< unsigned char > data_
 
mutex_t my_mutex_
 

Additional Inherited Members

- Public Types inherited from nav_core2::Costmap
typedef boost::recursive_mutex mutex_t
 
typedef std::shared_ptr< CostmapPtr
 
- Static Public Attributes inherited from nav_core2::Costmap
static const unsigned char FREE_SPACE
 
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
 
static const unsigned char LETHAL_OBSTACLE
 
static const unsigned char NO_INFORMATION
 

Detailed Description

An instantiation of the Costmap class that simply populates the grid from an image.

Definition at line 48 of file easy_costmap.h.

Constructor & Destructor Documentation

global_planner_tests::EasyCostmap::EasyCostmap ( const std::string &  filename,
const double  resolution = 0.1,
const bool  origin_at_center = false 
)
explicit

Constructor, loads directly from an image filename.

Parameters
filenameThe filename for the image to load
resolutionRather than loading from a yaml file, you can specify the resolution here
origin_at_centerIf true, will put the origin of the map at the center, rather than the bottom left

Definition at line 45 of file easy_costmap.cpp.

global_planner_tests::EasyCostmap::EasyCostmap ( )
inline

Empty constructor. You need to call loadMapFromFile afterward.

Definition at line 62 of file easy_costmap.h.

Member Function Documentation

void global_planner_tests::EasyCostmap::loadMapFromFile ( const std::string &  filename,
const double  resolution = 0.1,
const bool  origin_at_center = false 
)

Definition at line 50 of file easy_costmap.cpp.

void global_planner_tests::EasyCostmap::reset ( )
override

Definition at line 66 of file easy_costmap.cpp.

Member Data Documentation

nav_msgs::OccupancyGrid global_planner_tests::EasyCostmap::original_grid_
protected

Definition at line 71 of file easy_costmap.h.


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


global_planner_tests
Author(s):
autogenerated on Wed Jun 26 2019 20:06:09