Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
get_next_few_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/get_next_few_goals_action.hpp"
22 
23 namespace nav2_behavior_tree
24 {
25 
26 GetNextFewGoals::GetNextFewGoals(
27  const std::string & name,
28  const BT::NodeConfiguration & conf)
29 : BT::ActionNodeBase(name, conf)
30 {
31 }
32 
33 inline BT::NodeStatus GetNextFewGoals::tick()
34 {
35  setStatus(BT::NodeStatus::RUNNING);
36 
37  nav_msgs::msg::Goals input_goals, output_goals;
38  unsigned int num_goals;
39  getInput("input_goals", input_goals);
40  getInput("num_goals", num_goals);
41 
42  if (input_goals.goals.empty()) {
43  return BT::NodeStatus::FAILURE;
44  }
45 
46  output_goals.header = input_goals.header;
47  for (unsigned int i = 0; i < num_goals && i < input_goals.goals.size(); ++i) {
48  output_goals.goals.push_back(input_goals.goals[i]);
49  }
50  setOutput("output_goals", output_goals);
51  return BT::NodeStatus::SUCCESS;
52 }
53 
54 } // namespace nav2_behavior_tree
55 
56 #include "behaviortree_cpp/bt_factory.h"
57 BT_REGISTER_NODES(factory)
58 {
59  factory.registerNodeType<nav2_behavior_tree::GetNextFewGoals>("GetNextFewGoals");
60 }