Class GraphSaver

Class Documentation

class GraphSaver

An object to save graph objects to a file.

Public Functions

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

A constructor for nav2_route::GraphSaver.

Parameters:
  • node – Lifecycle node encapsulated by the GraphSaver

  • tf – A tf buffer

  • frame – Coordinate frame that the graph belongs to

~GraphSaver() = default

A destructor for nav2_route::GraphSaver.

bool saveGraphToFile(Graph &graph, std::string filepath = "")

Saves a graph object to a file.

Parameters:
  • graph – Graph to save

  • filepath – The filepath to the graph data

Returns:

bool If successful

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("GraphSaver")}
pluginlib::ClassLoader<GraphFileSaver> plugin_loader_
GraphFileSaver::Ptr graph_file_saver_
std::string default_plugin_id_
std::string plugin_type_