|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A table of motion primitives and related functions. More...
#include <nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp>
Public Member Functions | |
| HybridMotionTable () | |
| A constructor for nav2_smac_planner::HybridMotionTable. | |
| void | initDubin (unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info) |
| Initializing using Dubin model. More... | |
| void | initReedsShepp (unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info) |
| Initializing using Reeds-Shepp model. More... | |
| MotionPoses | getProjections (const NodeHybrid *node) |
| Get projections of motion models. More... | |
| unsigned int | getClosestAngularBin (const double &theta) |
| Get the angular bin to use from a raw orientation. More... | |
| float | getAngleFromBin (const unsigned int &bin_idx) |
| Get the raw orientation from an angular bin. More... | |
A table of motion primitives and related functions.
Definition at line 59 of file node_hybrid.hpp.
| float nav2_smac_planner::HybridMotionTable::getAngleFromBin | ( | const unsigned int & | bin_idx | ) |
Get the raw orientation from an angular bin.
| bin_idx | Index of the bin |
Definition at line 257 of file node_hybrid.cpp.
| unsigned int nav2_smac_planner::HybridMotionTable::getClosestAngularBin | ( | const double & | theta | ) |
Get the angular bin to use from a raw orientation.
| theta | Angle in radians |
Definition at line 251 of file node_hybrid.cpp.
| MotionPoses nav2_smac_planner::HybridMotionTable::getProjections | ( | const NodeHybrid * | node | ) |
Get projections of motion models.
| node | Ptr to NodeHybrid |
Definition at line 222 of file node_hybrid.cpp.
Referenced by nav2_smac_planner::NodeHybrid::getNeighbors().

| void nav2_smac_planner::HybridMotionTable::initDubin | ( | unsigned int & | size_x_in, |
| unsigned int & | size_y_in, | ||
| unsigned int & | angle_quantization_in, | ||
| SearchInfo & | search_info | ||
| ) |
Initializing using Dubin model.
| size_x_in | Size of costmap in X |
| size_y_in | Size of costmap in Y |
| angle_quantization_in | Size of costmap in bin sizes |
| search_info | Parameters for searching |
Definition at line 55 of file node_hybrid.cpp.
| void nav2_smac_planner::HybridMotionTable::initReedsShepp | ( | unsigned int & | size_x_in, |
| unsigned int & | size_y_in, | ||
| unsigned int & | angle_quantization_in, | ||
| SearchInfo & | search_info | ||
| ) |
Initializing using Reeds-Shepp model.
| size_x_in | Size of costmap in X |
| size_y_in | Size of costmap in Y |
| angle_quantization_in | Size of costmap in bin sizes |
| search_info | Parameters for searching |
Definition at line 148 of file node_hybrid.cpp.