Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
An object to save graph objects to a file. More...
#include <nav2_route/include/nav2_route/graph_saver.hpp>
Public Member Functions | |
GraphSaver (nav2_util::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< GraphFileSaver > | plugin_loader_ |
GraphFileSaver::Ptr | graph_file_saver_ |
std::string | default_plugin_id_ |
std::string | plugin_type_ |
An object to save graph objects to a file.
Definition at line 41 of file graph_saver.hpp.
|
explicit |
A constructor for nav2_route::GraphSaver.
node | Lifecycle node encapsulated by the GraphSaver |
tf | A tf buffer |
frame | Coordinate frame that the graph belongs to |
Definition at line 23 of file graph_saver.cpp.
bool nav2_route::GraphSaver::saveGraphToFile | ( | Graph & | graph, |
std::string | filepath = "" |
||
) |
Saves a graph object to a file.
graph | Graph to save |
filepath | The filepath to the graph data |
Definition at line 64 of file graph_saver.cpp.
References transformGraph().
bool nav2_route::GraphSaver::transformGraph | ( | Graph & | graph | ) |
Transform the coordinates in the graph to the route frame.
[in/out] | graph The graph to be transformed |
Definition at line 100 of file graph_saver.cpp.
Referenced by saveGraphToFile().