Class Costmap

Class Documentation

class Costmap

Class for a single layered costmap initialized from an occupancy grid representing the map.

Public Types

typedef uint8_t CostValue

Public 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.

Parameters:
  • 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

Costmap() = delete
~Costmap()
void set_static_map(const nav_msgs::msg::OccupancyGrid &occupancy_grid)

Set the static map of this costmap.

Parameters:

occupancy_grid – Occupancy grid to populate this costmap with

void set_test_costmap(const TestCostmap &testCostmapType)

Set the test costmap type of this costmap.

Parameters:

testCostmapType – Type of stored costmap to use

nav2_msgs::msg::Costmap get_costmap(const nav2_msgs::msg::CostmapMetaData &specifications)

Get a costmap message from this object.

Parameters:

specifications – Parameters of costmap

Returns:

Costmap msg of this costmap

inline nav2_msgs::msg::CostmapMetaData get_properties()

Get a metadata message from this object.

Returns:

Costmap metadata of this costmap

bool is_free(const unsigned int x_coordinate, const unsigned int y_coordinate) const

Get whether some coordinates are free.

Returns:

bool if free

bool is_free(const unsigned int index) const

Get whether some index in the costmap is free.

Returns:

bool if free

Public Static Attributes

static const CostValue no_information
static const CostValue lethal_obstacle
static const CostValue inscribed_inflated_obstacle
static const CostValue medium_cost
static const CostValue free_space