Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
extract_route_nodes_as_goals_action.cpp
1 // Copyright (c) 2025 Open Navigation LLC
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 <string>
16 #include <memory>
17 #include <limits>
18 
19 #include "nav2_util/geometry_utils.hpp"
20 
21 #include "nav2_behavior_tree/plugins/action/extract_route_nodes_as_goals_action.hpp"
22 
23 namespace nav2_behavior_tree
24 {
25 
26 ExtractRouteNodesAsGoals::ExtractRouteNodesAsGoals(
27  const std::string & name,
28  const BT::NodeConfiguration & conf)
29 : BT::ActionNodeBase(name, conf)
30 {
31 }
32 
33 inline BT::NodeStatus ExtractRouteNodesAsGoals::tick()
34 {
35  setStatus(BT::NodeStatus::RUNNING);
36 
37  nav2_msgs::msg::Route route;
38  getInput("route", route);
39 
40  if (route.nodes.empty()) {
41  return BT::NodeStatus::FAILURE;
42  }
43 
44  nav_msgs::msg::Goals goals;
45  goals.header = route.header;
46  goals.goals.reserve(route.nodes.size());
47 
48  for (const auto & node : route.nodes) {
49  geometry_msgs::msg::PoseStamped goal;
50  goal.header = route.header;
51  goal.pose.position.x = node.position.x;
52  goal.pose.position.y = node.position.y;
53  goals.goals.push_back(goal);
54  }
55 
56  setOutput("goals", goals);
57  return BT::NodeStatus::SUCCESS;
58 }
59 
60 } // namespace nav2_behavior_tree
61 
62 #include "behaviortree_cpp/bt_factory.h"
63 BT_REGISTER_NODES(factory)
64 {
65  factory.registerNodeType<nav2_behavior_tree::ExtractRouteNodesAsGoals>(
66  "ExtractRouteNodesAsGoals");
67 }