15 #ifndef NAV2_ROUTE__GRAPH_SAVER_HPP_
16 #define NAV2_ROUTE__GRAPH_SAVER_HPP_
21 #include <unordered_map>
22 #include <nlohmann/json.hpp>
23 #include <pluginlib/class_loader.hpp>
25 #include "nav2_ros_common/lifecycle_node.hpp"
26 #include "tf2_ros/buffer.hpp"
27 #include "tf2_ros/transform_listener.hpp"
28 #include "nav2_ros_common/node_utils.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_route/types.hpp"
31 #include "nav2_route/interfaces/graph_file_saver.hpp"
32 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
51 nav2::LifecycleNode::SharedPtr node,
52 std::shared_ptr<tf2_ros::Buffer> tf,
53 const std::string frame);
68 std::string filepath =
"");
78 std::string route_frame_, graph_filepath_;
79 std::shared_ptr<tf2_ros::Buffer> tf_;
80 rclcpp::Logger logger_{rclcpp::get_logger(
"GraphSaver")};
83 pluginlib::ClassLoader<GraphFileSaver> plugin_loader_;
84 GraphFileSaver::Ptr graph_file_saver_;
85 std::string default_plugin_id_;
86 std::string plugin_type_;
An object to save graph objects to a file.
bool saveGraphToFile(Graph &graph, std::string filepath="")
Saves a graph object to a file.
GraphSaver(nav2::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf, const std::string frame)
A constructor for nav2_route::GraphSaver.
~GraphSaver()=default
A destructor for nav2_route::GraphSaver.
bool transformGraph(Graph &graph)
Transform the coordinates in the graph to the route frame.