|
EasyNav Costmap Stack
|
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> | |
| T | yaml_get_value (const YAML::Node &node, const std::string &key) |
| Get the given subnode value. | |
Provides a mapping for often used cost values.
|
strong |
| enum LOAD_MAP_STATUS |
|
strong |
| 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.
| path | Path containing the poses that are planned |
| start_index | Optional 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. |
| void checkSaveParameters | ( | SaveParameters & | save_parameters | ) |
Checks map saving parameters for consistency.
| save_parameters | Map saving parameters. NOTE: save_parameters could be updated during function execution. |
| std::exception | in case of inconsistent parameters |
| 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.
| pos1 | First point |
| pos1 | Second point |
| is_3d | True if a true L2 distance is desired (default false) |
| 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.
| pos1 | First pose |
| pos1 | Second pose |
| is_3d | True if a true L2 distance is desired (default false) |
| 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.
| pos1 | First pose |
| pos1 | Second pose |
| is_3d | True if a true L2 distance is desired (default false) |
| std::string expand_user_home_dir_if_needed | ( | std::string | yaml_filename, |
| std::string | home_dir ) |
Expand ~/ to home user dir.
| yaml_filename | Name of input YAML file. |
| home_dir | Expanded ~/home dir or empty string if HOME not set |
~/ not expanded | double extractYaw | ( | const tf2::Transform & | transform | ) |
| 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_parameters | Parameters of loading map |
| map | Output loaded map |
| std::exception |
| 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.
| yaml_file | Name of input YAML file |
| map | Output loaded map |
| LoadParameters loadMapYaml | ( | const std::string & | yaml_filename | ) |
Load and parse the given YAML file.
| yaml_filename | Name of the map file passed though parameter |
| YAML::Exception |
| MapMode map_mode_from_string | ( | std::string | map_mode_name | ) |
Convert the name of a map mode to a MapMode enum.
| map_mode_name | Name of the map mode |
| std::invalid_argument | if the name does not name a map mode |
| const char * map_mode_to_string | ( | MapMode | map_mode | ) |
Convert a MapMode enum to the name of the map mode.
| map_mode | Mode for the map |
| std::invalid_argument | if the given value is not a defined map mode |
| 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.
| angle | Yaw angle to generate a quaternion from |
| void printTransform | ( | const tf2::Transform & | tf | ) |
| bool saveMapToFile | ( | const nav_msgs::msg::OccupancyGrid & | map, |
| const SaveParameters & | save_parameters ) |
Write OccupancyGrid map to file.
| map | OccupancyGrid map data |
| save_parameters | Map saving parameters. |
| void tryWriteMapToFile | ( | const nav_msgs::msg::OccupancyGrid & | map, |
| const SaveParameters & | save_parameters ) |
Tries to write map data into a file.
| map | Occupancy grid data |
| save_parameters | Map saving parameters |
| std::exception | in case of problem |
| 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
| YAML::Exception |