Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
An action server to load graph files into the graph object for search and processing. More...
#include <nav2_route/include/nav2_route/graph_loader.hpp>
Public Member Functions | |
GraphLoader (rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf, const std::string frame) | |
A constructor for nav2_route::GraphLoader. More... | |
~GraphLoader ()=default | |
A destructor for nav2_route::GraphLoader. | |
bool | loadGraphFromFile (Graph &graph, GraphToIDMap &idx_map, const std::string &filepath) |
Loads a graph object with file information from a filepath. More... | |
bool | loadGraphFromParameter (Graph &graph, GraphToIDMap &idx_map) |
Loads a graph object with file information from ROS parameter, if provided. More... | |
bool | transformGraph (Graph &graph) |
Transform the coordinates in the graph to the route frame. More... | |
Protected Attributes | |
std::string | route_frame_ |
std::string | graph_filepath_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("GraphLoader")} |
pluginlib::ClassLoader< GraphFileLoader > | plugin_loader_ |
GraphFileLoader::Ptr | graph_file_loader_ |
std::string | default_plugin_id_ |
std::string | plugin_type_ |
An action server to load graph files into the graph object for search and processing.
Definition at line 41 of file graph_loader.hpp.
|
explicit |
A constructor for nav2_route::GraphLoader.
options | Additional options to control creation of the node. |
Definition at line 23 of file graph_loader.cpp.
bool nav2_route::GraphLoader::loadGraphFromFile | ( | Graph & | graph, |
GraphToIDMap & | idx_map, | ||
const std::string & | filepath | ||
) |
Loads a graph object with file information from a filepath.
graph | Graph to populate |
idx_map | A map translating nodeid's to graph idxs for use in graph modification services and idx-based route planning requests. This is much faster than using a map the full graph data structure. |
filepath | The filepath to the graph data |
graph_file_loader_id | The id of the GraphFileLoader |
Definition at line 64 of file graph_loader.cpp.
References transformGraph().
bool nav2_route::GraphLoader::loadGraphFromParameter | ( | Graph & | graph, |
GraphToIDMap & | idx_map | ||
) |
Loads a graph object with file information from ROS parameter, if provided.
graph | Graph to populate |
idx_map | A map translating nodeid's to graph idxs for use in graph modification services and idx-based route planning requests. This is much faster than using a map the full graph data structure. |
graph_file_loader_id | The id of the GraphFileLoader |
Definition at line 93 of file graph_loader.cpp.
References transformGraph().
bool nav2_route::GraphLoader::transformGraph | ( | Graph & | graph | ) |
Transform the coordinates in the graph to the route frame.
[in/out] | graph The graph to be transformed |
Definition at line 121 of file graph_loader.cpp.
Referenced by loadGraphFromFile(), and loadGraphFromParameter().