Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_route::GraphSaver Class Reference

An object to save graph objects to a file. More...

#include <nav2_route/include/nav2_route/graph_saver.hpp>

Collaboration diagram for nav2_route::GraphSaver:
Collaboration graph
[legend]

Public Member Functions

 GraphSaver (nav2::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf, const std::string frame)
 A constructor for nav2_route::GraphSaver. More...
 
 ~GraphSaver ()=default
 A destructor for nav2_route::GraphSaver.
 
bool saveGraphToFile (Graph &graph, std::string filepath="")
 Saves a graph object to a file. 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("GraphSaver")}
 
pluginlib::ClassLoader< GraphFileSaverplugin_loader_
 
GraphFileSaver::Ptr graph_file_saver_
 
std::string default_plugin_id_
 
std::string plugin_type_
 

Detailed Description

An object to save graph objects to a file.

Definition at line 41 of file graph_saver.hpp.

Constructor & Destructor Documentation

◆ GraphSaver()

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

A constructor for nav2_route::GraphSaver.

Parameters
nodeLifecycle node encapsulated by the GraphSaver
tfA tf buffer
frameCoordinate frame that the graph belongs to

Definition at line 23 of file graph_saver.cpp.

Member Function Documentation

◆ saveGraphToFile()

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

Saves a graph object to a file.

Parameters
graphGraph to save
filepathThe filepath to the graph data
Returns
bool If successful

Definition at line 64 of file graph_saver.cpp.

References transformGraph().

Here is the call graph for this function:

◆ transformGraph()

bool nav2_route::GraphSaver::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

Definition at line 100 of file graph_saver.cpp.

Referenced by saveGraphToFile().

Here is the caller graph for this function:

The documentation for this class was generated from the following files: