An instantiation of the Costmap class that simply populates the grid from an image. More...
#include <easy_costmap.h>

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. | |
| EasyCostmap () | |
| Empty constructor. You need to call loadMapFromFile afterward. | |
| void | loadMapFromFile (const std::string &filename, const double resolution=0.1, const bool origin_at_center=false) |
| void | reset () override |
Protected Attributes | |
| nav_msgs::OccupancyGrid | original_grid_ |
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.
| 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 |
||
| ) |
Definition at line 50 of file easy_costmap.cpp.
| void global_planner_tests::EasyCostmap::reset | ( | ) | [override] |
Reimplemented from nav_core2::BasicCostmap.
Definition at line 66 of file easy_costmap.cpp.
nav_msgs::OccupancyGrid global_planner_tests::EasyCostmap::original_grid_ [protected] |
Definition at line 71 of file easy_costmap.h.