15 #ifndef NAV2_ROUTE__GRAPH_LOADER_HPP_
16 #define NAV2_ROUTE__GRAPH_LOADER_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_loader.hpp"
32 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
49 nav2::LifecycleNode::SharedPtr node,
50 std::shared_ptr<tf2_ros::Buffer> tf,
51 const std::string frame);
70 GraphToIDMap & idx_map,
71 const std::string & filepath);
84 GraphToIDMap & idx_map);
94 std::string route_frame_, graph_filepath_;
95 std::shared_ptr<tf2_ros::Buffer> tf_;
96 rclcpp::Logger logger_{rclcpp::get_logger(
"GraphLoader")};
99 pluginlib::ClassLoader<GraphFileLoader> plugin_loader_;
100 GraphFileLoader::Ptr graph_file_loader_;
101 std::string default_plugin_id_;
102 std::string plugin_type_;
An action server to load graph files into the graph object for search and processing.
bool transformGraph(Graph &graph)
Transform the coordinates in the graph to the route frame.
~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.
bool loadGraphFromParameter(Graph &graph, GraphToIDMap &idx_map)
Loads a graph object with file information from ROS parameter, if provided.
GraphLoader(nav2::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf, const std::string frame)
A constructor for nav2_route::GraphLoader.