EasyNav Costmap Stack
Loading...
Searching...
No Matches
easynav Namespace Reference

Provides a mapping for often used cost values. More...

Classes

class  AMCLLocalizer
 A localization method implementing a simplified AMCL (Adaptive Monte Carlo Localization) approach. More...
 
class  CellData
 
class  Costmap2D
 A 2D costmap provides a mapping between points in the world and their associated "costs". More...
 
class  CostmapFilter
 
class  CostmapMapsManager
 A plugin-based map manager using the SimpleMap data structure. More...
 
class  CostmapPlanner
 A planner implementing the A* algorithm on a Costmap2D grid. More...
 
struct  GridNode
 
class  InflationFilter
 
struct  LoadParameters
 
struct  MapLocation
 
class  ObstacleFilter
 
struct  Particle
 Structure representing a single particle in the AMCL algorithm. More...
 
struct  SaveParameters
 

Enumerations

enum class  CombinationMethod : int { Overwrite = 0 , Max = 1 , MaxWithoutUnknownOverwrite = 2 }
 
enum  LOAD_MAP_STATUS { LOAD_MAP_SUCCESS , MAP_DOES_NOT_EXIST , INVALID_MAP_METADATA , INVALID_MAP_DATA }
 
enum class  MapMode { Trinary , Scale , Raw }
 

Functions

double calculate_path_length (const nav_msgs::msg::Path &path, size_t start_index=0)
 Calculate the length of the provided path, starting at the provided index.
 
void checkSaveParameters (SaveParameters &save_parameters)
 Checks map saving parameters for consistency.
 
tf2::Matrix3x3 computeCovariance (const std::vector< Particle > &particles, std::size_t start, std::size_t count, const tf2::Vector3 &mean)
 
tf2::Vector3 computeMean (const std::vector< Particle > &particles, std::size_t start, std::size_t count)
 
double computeYawVariance (const std::vector< Particle > &particles, std::size_t start, std::size_t count)
 
double euclidean_distance (const geometry_msgs::msg::Point &pos1, const geometry_msgs::msg::Point &pos2, const bool is_3d=false)
 Get the euclidean distance between 2 geometry_msgs::Points.
 
double euclidean_distance (const geometry_msgs::msg::Pose &pos1, const geometry_msgs::msg::Pose &pos2, const bool is_3d=false)
 Get the L2 distance between 2 geometry_msgs::Poses.
 
double euclidean_distance (const geometry_msgs::msg::PoseStamped &pos1, const geometry_msgs::msg::PoseStamped &pos2, const bool is_3d=false)
 Get the L2 distance between 2 geometry_msgs::PoseStamped.
 
std::string expand_user_home_dir_if_needed (std::string yaml_filename, std::string home_dir)
 Expand ~/ to home user dir.
 
double extractYaw (const tf2::Transform &transform)
 
template<typename Iter, typename Getter>
Iter first_after_integrated_distance (Iter begin, Iter end, Getter getCompareVal)
 Find first element in iterator that is greater integrated distance than comparevalue.
 
std::string get_home_dir ()
 
void loadMapFromFile (const LoadParameters &load_parameters, nav_msgs::msg::OccupancyGrid &map)
 Load the image from map file and generate an OccupancyGrid.
 
LOAD_MAP_STATUS loadMapFromYaml (const std::string &yaml_file, nav_msgs::msg::OccupancyGrid &map)
 Load the map YAML, image from map file and generate an OccupancyGrid.
 
LoadParameters loadMapYaml (const std::string &yaml_filename)
 Load and parse the given YAML file.
 
MapMode map_mode_from_string (std::string map_mode_name)
 Convert the name of a map mode to a MapMode enum.
 
const char * map_mode_to_string (MapMode map_mode)
 Convert a MapMode enum to the name of the map mode.
 
template<typename Iter, typename Getter>
Iter min_by (Iter begin, Iter end, Getter getCompareVal)
 Find element in iterator with the minimum calculated value.
 
geometry_msgs::msg::Quaternion orientationAroundZAxis (double angle)
 Get a geometry_msgs Quaternion from a yaw angle.
 
void printTransform (const tf2::Transform &tf)
 
bool saveMapToFile (const nav_msgs::msg::OccupancyGrid &map, const SaveParameters &save_parameters)
 Write OccupancyGrid map to file.
 
void tryWriteMapToFile (const nav_msgs::msg::OccupancyGrid &map, const SaveParameters &save_parameters)
 Tries to write map data into a file.
 
template<typename T>
yaml_get_value (const YAML::Node &node, const std::string &key)
 Get the given subnode value.
 

Detailed Description

Provides a mapping for often used cost values.

Enumeration Type Documentation

◆ CombinationMethod

enum class CombinationMethod : int
strong
Enumerator
Overwrite 

Overwrite means every valid value from this layer is written into the master grid (does not copy NO_INFORMATION)

Max 

Sets the new value to the maximum of the master_grid's value and this layer's value.

If the master value is NO_INFORMATION, it is overwritten. If the layer's value is NO_INFORMATION, the master value does not change

MaxWithoutUnknownOverwrite 

Sets the new value to the maximum of the master_grid's value and this layer's value.

If the master value is NO_INFORMATION, it is NOT overwritten. If the layer's value is NO_INFORMATION, the master value does not change.

◆ LOAD_MAP_STATUS

Enumerator
LOAD_MAP_SUCCESS 
MAP_DOES_NOT_EXIST 
INVALID_MAP_METADATA 
INVALID_MAP_DATA 

◆ MapMode

enum class MapMode
strong
Enumerator
Trinary 

Together with associated threshold values (occupied and free): lightness >= occupied threshold - Occupied (100) ... (anything in between) - Unknown (-1) lightness <= free threshold - Free (0)

Scale 

Together with associated threshold values (occupied and free): alpha < 1.0 - Unknown (-1) lightness >= occ_th - Occupied (100) ... (linearly interpolate to) lightness <= free_th - Free (0)

Raw 

Lightness = 0 - Free (0) ... (linearly interpolate to) Lightness = 100 - Occupied (100) Lightness >= 101 - Unknown.

Function Documentation

◆ calculate_path_length()

double calculate_path_length ( const nav_msgs::msg::Path & path,
size_t start_index = 0 )

Calculate the length of the provided path, starting at the provided index.

Parameters
pathPath containing the poses that are planned
start_indexOptional argument specifying the starting index for the calculation of path length. Provide this if you want to calculate length of a subset of the path.
Returns
double Path length

◆ checkSaveParameters()

void checkSaveParameters ( SaveParameters & save_parameters)

Checks map saving parameters for consistency.

Parameters
save_parametersMap saving parameters. NOTE: save_parameters could be updated during function execution.
Exceptions
std::exceptionin case of inconsistent parameters

◆ computeCovariance()

tf2::Matrix3x3 computeCovariance ( const std::vector< Particle > & particles,
std::size_t start,
std::size_t count,
const tf2::Vector3 & mean )

◆ computeMean()

tf2::Vector3 computeMean ( const std::vector< Particle > & particles,
std::size_t start,
std::size_t count )

◆ computeYawVariance()

double computeYawVariance ( const std::vector< Particle > & particles,
std::size_t start,
std::size_t count )

◆ euclidean_distance() [1/3]

double euclidean_distance ( const geometry_msgs::msg::Point & pos1,
const geometry_msgs::msg::Point & pos2,
const bool is_3d = false )

Get the euclidean distance between 2 geometry_msgs::Points.

Parameters
pos1First point
pos1Second point
is_3dTrue if a true L2 distance is desired (default false)
Returns
double L2 distance

◆ euclidean_distance() [2/3]

double euclidean_distance ( const geometry_msgs::msg::Pose & pos1,
const geometry_msgs::msg::Pose & pos2,
const bool is_3d = false )

Get the L2 distance between 2 geometry_msgs::Poses.

Parameters
pos1First pose
pos1Second pose
is_3dTrue if a true L2 distance is desired (default false)
Returns
double euclidean distance

◆ euclidean_distance() [3/3]

double euclidean_distance ( const geometry_msgs::msg::PoseStamped & pos1,
const geometry_msgs::msg::PoseStamped & pos2,
const bool is_3d = false )

Get the L2 distance between 2 geometry_msgs::PoseStamped.

Parameters
pos1First pose
pos1Second pose
is_3dTrue if a true L2 distance is desired (default false)
Returns
double L2 distance

◆ expand_user_home_dir_if_needed()

std::string expand_user_home_dir_if_needed ( std::string yaml_filename,
std::string home_dir )

Expand ~/ to home user dir.

Parameters
yaml_filenameName of input YAML file.
home_dirExpanded ~/home dir or empty string if HOME not set
Returns
Expanded string or input string if ~/ not expanded

◆ extractYaw()

double extractYaw ( const tf2::Transform & transform)

◆ first_after_integrated_distance()

template<typename Iter, typename Getter>
Iter first_after_integrated_distance ( Iter begin,
Iter end,
Getter getCompareVal )

Find first element in iterator that is greater integrated distance than comparevalue.

◆ get_home_dir()

std::string get_home_dir ( )

◆ loadMapFromFile()

void loadMapFromFile ( const LoadParameters & load_parameters,
nav_msgs::msg::OccupancyGrid & map )

Load the image from map file and generate an OccupancyGrid.

Parameters
load_parametersParameters of loading map
mapOutput loaded map
Exceptions
std::exception

◆ loadMapFromYaml()

LOAD_MAP_STATUS loadMapFromYaml ( const std::string & yaml_file,
nav_msgs::msg::OccupancyGrid & map )

Load the map YAML, image from map file and generate an OccupancyGrid.

Parameters
yaml_fileName of input YAML file
mapOutput loaded map
Returns
status of map loaded

◆ loadMapYaml()

LoadParameters loadMapYaml ( const std::string & yaml_filename)

Load and parse the given YAML file.

Parameters
yaml_filenameName of the map file passed though parameter
Returns
Map loading parameters obtained from YAML file
Exceptions
YAML::Exception

◆ map_mode_from_string()

MapMode map_mode_from_string ( std::string map_mode_name)

Convert the name of a map mode to a MapMode enum.

Parameters
map_mode_nameName of the map mode
Exceptions
std::invalid_argumentif the name does not name a map mode
Returns
map mode corresponding to the string

◆ map_mode_to_string()

const char * map_mode_to_string ( MapMode map_mode)

Convert a MapMode enum to the name of the map mode.

Parameters
map_modeMode for the map
Returns
String identifier of the given map mode
Exceptions
std::invalid_argumentif the given value is not a defined map mode

◆ min_by()

template<typename Iter, typename Getter>
Iter min_by ( Iter begin,
Iter end,
Getter getCompareVal )

Find element in iterator with the minimum calculated value.

◆ orientationAroundZAxis()

geometry_msgs::msg::Quaternion orientationAroundZAxis ( double angle)

Get a geometry_msgs Quaternion from a yaw angle.

Parameters
angleYaw angle to generate a quaternion from
Returns
geometry_msgs Quaternion

◆ printTransform()

void printTransform ( const tf2::Transform & tf)

◆ saveMapToFile()

bool saveMapToFile ( const nav_msgs::msg::OccupancyGrid & map,
const SaveParameters & save_parameters )

Write OccupancyGrid map to file.

Parameters
mapOccupancyGrid map data
save_parametersMap saving parameters.
Returns
true or false

◆ tryWriteMapToFile()

void tryWriteMapToFile ( const nav_msgs::msg::OccupancyGrid & map,
const SaveParameters & save_parameters )

Tries to write map data into a file.

Parameters
mapOccupancy grid data
save_parametersMap saving parameters
Exceptions
std::exceptionin case of problem

◆ yaml_get_value()

template<typename T>
T yaml_get_value ( const YAML::Node & node,
const std::string & key )

Get the given subnode value.

The only reason this function exists is to wrap the exceptions in slightly nicer error messages, including the name of the failed key

Exceptions
YAML::Exception