Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Class for a single layered costmap initialized from an occupancy grid representing the map. More...
#include <nav2_util/include/nav2_util/costmap.hpp>
Public Types | |
typedef uint8_t | CostValue |
Public Member Functions | |
Costmap (rclcpp::Node *node, bool trinary_costmap=true, bool track_unknown_space=true, int lethal_threshold=100, int unknown_cost_value=-1) | |
A constructor for nav2_util::Costmap. More... | |
void | set_static_map (const nav_msgs::msg::OccupancyGrid &occupancy_grid) |
Set the static map of this costmap. More... | |
void | set_test_costmap (const TestCostmap &testCostmapType) |
Set the test costmap type of this costmap. More... | |
nav2_msgs::msg::Costmap | get_costmap (const nav2_msgs::msg::CostmapMetaData &specifications) |
Get a costmap message from this object. More... | |
nav2_msgs::msg::CostmapMetaData | get_properties () |
Get a metadata message from this object. More... | |
bool | is_free (const unsigned int x_coordinate, const unsigned int y_coordinate) const |
Get whether some coordinates are free. More... | |
bool | is_free (const unsigned int index) const |
Get whether some index in the costmap is free. More... | |
Class for a single layered costmap initialized from an occupancy grid representing the map.
Definition at line 44 of file costmap.hpp.
nav2_util::Costmap::Costmap | ( | rclcpp::Node * | node, |
bool | trinary_costmap = true , |
||
bool | track_unknown_space = true , |
||
int | lethal_threshold = 100 , |
||
int | unknown_cost_value = -1 |
||
) |
A constructor for nav2_util::Costmap.
node | Ptr to a node |
trinary_costmap | Whether the costmap should be trinary |
track_unknown_space | Whether to track unknown space in costmap |
lethal_threshold | The lethal space cost threshold to use |
unknown_cost_value | Internal costmap cell value for unknown space |
Definition at line 34 of file costmap.cpp.
nav2_msgs::msg::Costmap nav2_util::Costmap::get_costmap | ( | const nav2_msgs::msg::CostmapMetaData & | specifications | ) |
Get a costmap message from this object.
specifications | Parameters of costmap |
Definition at line 108 of file costmap.cpp.
|
inline |
Get a metadata message from this object.
Definition at line 86 of file costmap.hpp.
bool nav2_util::Costmap::is_free | ( | const unsigned int | index | ) | const |
Get whether some index in the costmap is free.
Definition at line 257 of file costmap.cpp.
bool nav2_util::Costmap::is_free | ( | const unsigned int | x_coordinate, |
const unsigned int | y_coordinate | ||
) | const |
Get whether some coordinates are free.
Definition at line 250 of file costmap.cpp.
void nav2_util::Costmap::set_static_map | ( | const nav_msgs::msg::OccupancyGrid & | occupancy_grid | ) |
Set the static map of this costmap.
occupancy_grid | Occupancy grid to populate this costmap with |
Definition at line 52 of file costmap.cpp.
void nav2_util::Costmap::set_test_costmap | ( | const TestCostmap & | testCostmapType | ) |
Set the test costmap type of this costmap.
testCostmapType | Type of stored costmap to use |
Definition at line 87 of file costmap.cpp.