Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
graph_saver.cpp
1 // Copyright (c) 2024 John Chrosniak
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <memory>
16 
17 #include "nav2_route/graph_saver.hpp"
18 #include "ament_index_cpp/get_package_share_directory.hpp"
19 
20 namespace nav2_route
21 {
22 
24  nav2_util::LifecycleNode::SharedPtr node,
25  std::shared_ptr<tf2_ros::Buffer> tf,
26  const std::string frame)
27 : plugin_loader_("nav2_route", "nav2_route::GraphFileSaver"),
28  default_plugin_id_("GeoJsonGraphFileSaver")
29 {
30  logger_ = node->get_logger();
31  tf_ = tf;
32  route_frame_ = frame;
33 
34  nav2_util::declare_parameter_if_not_declared(
35  node, "graph_filepath", rclcpp::ParameterValue(std::string("")));
36  graph_filepath_ = node->get_parameter("graph_filepath").as_string();
37 
38  // Default Graph Parser
39  const std::string default_plugin_type = "nav2_route::GeoJsonGraphFileSaver";
40  nav2_util::declare_parameter_if_not_declared(
41  node, "graph_file_saver", rclcpp::ParameterValue(default_plugin_id_));
42  auto graph_file_saver_id = node->get_parameter("graph_file_saver").as_string();
43  if (graph_file_saver_id == default_plugin_id_) {
44  nav2_util::declare_parameter_if_not_declared(
45  node, default_plugin_id_ + ".plugin", rclcpp::ParameterValue(default_plugin_type));
46  }
47 
48  // Create graph file saver plugin
49  try {
50  plugin_type_ = nav2_util::get_plugin_type_param(node, graph_file_saver_id);
51  graph_file_saver_ = plugin_loader_.createSharedInstance((plugin_type_));
52  RCLCPP_INFO(
53  logger_, "Created GraphFileSaver %s of type %s",
54  graph_file_saver_id.c_str(), plugin_type_.c_str());
55  graph_file_saver_->configure(node);
56  } catch (pluginlib::PluginlibException & ex) {
57  RCLCPP_FATAL(
58  logger_,
59  "Failed to create GraphFileSaver. Exception: %s", ex.what());
60  throw ex;
61  }
62 }
63 
65  Graph & graph,
66  std::string filepath)
67 {
68  if (filepath.empty() && !graph_filepath_.empty()) {
69  RCLCPP_DEBUG(
70  logger_, "The graph filepath was not provided. "
71  "Setting to %s", graph_filepath_.c_str());
72  filepath = graph_filepath_;
73  } else if (filepath.empty() && graph_filepath_.empty()) {
74  // No graph to try to save
75  RCLCPP_WARN(
76  logger_,
77  "The graph filepath was not provided and no default was specified. "
78  "Failed to save the route graph.");
79  return false;
80  }
81 
82  RCLCPP_INFO(
83  logger_,
84  "Saving graph file from %s, by parser %s", filepath.c_str(), plugin_type_.c_str());
85 
86  if (!graph_file_saver_->saveGraphToFile(graph, filepath)) {
87  return false;
88  }
89 
90  if (!transformGraph(graph)) {
91  RCLCPP_WARN(
92  logger_,
93  "Failed to transform nodes graph file (%s) to %s!", filepath.c_str(), route_frame_.c_str());
94  return false;
95  }
96 
97  return true;
98 }
99 
100 bool GraphSaver::transformGraph(Graph & graph)
101 {
102  std::unordered_map<std::string, tf2::Transform> cached_transforms;
103  for (auto & node : graph) {
104  std::string node_frame = node.coords.frame_id;
105  if (node_frame.empty() || node_frame == route_frame_) {
106  // If there is no frame provided or the frame of the node is the same as the route graph
107  // then no transform is required
108  continue;
109  }
110  // Find the transform to convert node from node frame to route frame
111  if (cached_transforms.find(node_frame) == cached_transforms.end()) {
112  tf2::Transform tf_transform;
113  bool got_transform = nav2_util::getTransform(
114  node_frame, route_frame_, tf2::durationFromSec(0.1), tf_, tf_transform);
115 
116  if (!got_transform) {
117  RCLCPP_WARN(
118  logger_,
119  "Could not get transform from node frame %s to route frame %s",
120  node_frame.c_str(), route_frame_.c_str());
121  return false;
122  }
123 
124  cached_transforms.insert({node_frame, tf_transform});
125  }
126  // Apply the transform
127  tf2::Vector3 graph_coord(
128  node.coords.x,
129  node.coords.y,
130  0.0);
131 
132  tf2::Vector3 new_coord = cached_transforms[node_frame] * graph_coord;
133 
134  node.coords.x = static_cast<float>(new_coord.x());
135  node.coords.y = static_cast<float>(new_coord.y());
136  node.coords.frame_id = route_frame_;
137  }
138 
139  return true;
140 }
141 
142 } // namespace nav2_route
GraphSaver(nav2_util::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf, const std::string frame)
A constructor for nav2_route::GraphSaver.
Definition: graph_saver.cpp:23
bool saveGraphToFile(Graph &graph, std::string filepath="")
Saves a graph object to a file.
Definition: graph_saver.cpp:64
bool transformGraph(Graph &graph)
Transform the coordinates in the graph to the route frame.