Class GraphLoader

Class Documentation

class GraphLoader

An action server to load graph files into the graph object for search and processing.

Public Functions

explicit GraphLoader(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr<tf2_ros::Buffer> tf, const std::string frame)

A constructor for nav2_route::GraphLoader.

Parameters:

options – Additional options to control creation of the node.

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

Parameters:
  • 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

Returns:

bool If successful

bool loadGraphFromParameter(Graph &graph, GraphToIDMap &idx_map)

Loads a graph object with file information from ROS parameter, if provided.

Parameters:
  • 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

Returns:

bool If successful or none provided

bool transformGraph(Graph &graph)

Transform the coordinates in the graph to the route frame.

Parameters:

[in/out] – graph The graph to be transformed

Returns:

True if transformation was successful

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_