An instantiation of the Costmap class that simply populates the grid from an image.
More...
#include <easy_costmap.h>
|
| 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 |
|
unsigned int | getIndex (const unsigned int x, const unsigned int y) const |
|
mutex_t * | getMutex () 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 |
|
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 () |
|
An instantiation of the Costmap class that simply populates the grid from an image.
Definition at line 48 of file easy_costmap.h.
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
-
filename | The filename for the image to load |
resolution | Rather than loading from a yaml file, you can specify the resolution here |
origin_at_center | If 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.
void global_planner_tests::EasyCostmap::loadMapFromFile |
( |
const std::string & |
filename, |
|
|
const double |
resolution = 0.1 , |
|
|
const bool |
origin_at_center = false |
|
) |
| |
void global_planner_tests::EasyCostmap::reset |
( |
| ) |
|
|
override |
nav_msgs::OccupancyGrid global_planner_tests::EasyCostmap::original_grid_ |
|
protected |
The documentation for this class was generated from the following files: