Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Types | Public Member Functions | Static Public Attributes | List of all members
nav2_util::Costmap Class Reference

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

Static Public Attributes

static const CostValue no_information = 255
 
static const CostValue lethal_obstacle = 254
 
static const CostValue inscribed_inflated_obstacle = 253
 
static const CostValue medium_cost = 128
 
static const CostValue free_space = 0
 

Detailed Description

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

Definition at line 44 of file costmap.hpp.

Constructor & Destructor Documentation

◆ Costmap()

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.

Parameters
nodePtr to a node
trinary_costmapWhether the costmap should be trinary
track_unknown_spaceWhether to track unknown space in costmap
lethal_thresholdThe lethal space cost threshold to use
unknown_cost_valueInternal costmap cell value for unknown space

Definition at line 34 of file costmap.cpp.

Member Function Documentation

◆ get_costmap()

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

Get a costmap message from this object.

Parameters
specificationsParameters of costmap
Returns
Costmap msg of this costmap

Definition at line 108 of file costmap.cpp.

◆ get_properties()

nav2_msgs::msg::CostmapMetaData nav2_util::Costmap::get_properties ( )
inline

Get a metadata message from this object.

Returns
Costmap metadata of this costmap

Definition at line 86 of file costmap.hpp.

◆ is_free() [1/2]

bool nav2_util::Costmap::is_free ( const unsigned int  index) const

Get whether some index in the costmap is free.

Returns
bool if free

Definition at line 257 of file costmap.cpp.

◆ is_free() [2/2]

bool nav2_util::Costmap::is_free ( const unsigned int  x_coordinate,
const unsigned int  y_coordinate 
) const

Get whether some coordinates are free.

Returns
bool if free

Definition at line 250 of file costmap.cpp.

◆ set_static_map()

void nav2_util::Costmap::set_static_map ( const nav_msgs::msg::OccupancyGrid &  occupancy_grid)

Set the static map of this costmap.

Parameters
occupancy_gridOccupancy grid to populate this costmap with

Definition at line 52 of file costmap.cpp.

◆ set_test_costmap()

void nav2_util::Costmap::set_test_costmap ( const TestCostmap &  testCostmapType)

Set the test costmap type of this costmap.

Parameters
testCostmapTypeType of stored costmap to use

Definition at line 87 of file costmap.cpp.


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