Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
remove_in_collision_goals_action.hpp
1 // Copyright (c) 2024 Angsa Robotics
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_IN_COLLISION_GOALS_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_IN_COLLISION_GOALS_ACTION_HPP_
17 
18 #include <vector>
19 #include <memory>
20 #include <string>
21 
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 #include "nav_msgs/msg/goals.hpp"
24 #include "nav2_behavior_tree/bt_service_node.hpp"
25 #include "nav2_msgs/srv/get_costs.hpp"
26 #include "nav2_msgs/msg/waypoint_status.hpp"
27 
28 namespace nav2_behavior_tree
29 {
30 
37 class RemoveInCollisionGoals : public BtServiceNode<nav2_msgs::srv::GetCosts>
38 {
39 public:
46  const std::string & service_node_name,
47  const BT::NodeConfiguration & conf);
48 
53  void on_tick() override;
54 
55  BT::NodeStatus on_completion(std::shared_ptr<nav2_msgs::srv::GetCosts::Response> response)
56  override;
57 
58  static BT::PortsList providedPorts()
59  {
60  // Register JSON definitions for the types used in the ports
61  BT::RegisterJsonDefinition<nav_msgs::msg::Goals>();
62  BT::RegisterJsonDefinition<nav2_msgs::msg::WaypointStatus>();
63  BT::RegisterJsonDefinition<std::vector<nav2_msgs::msg::WaypointStatus>>();
64 
65  return providedBasicPorts(
66  {
67  BT::InputPort<nav_msgs::msg::Goals>("input_goals",
68  "Original goals to remove from"),
69  BT::InputPort<double>(
70  "cost_threshold", 254.0,
71  "Cost threshold for considering a goal in collision"),
72  BT::InputPort<bool>("use_footprint", true, "Whether to use footprint cost"),
73  BT::InputPort<bool>(
74  "consider_unknown_as_obstacle", false,
75  "Whether to consider unknown cost as obstacle"),
76  BT::OutputPort<nav_msgs::msg::Goals>("output_goals",
77  "Goals with in-collision goals removed"),
78  BT::InputPort<std::vector<nav2_msgs::msg::WaypointStatus>>("input_waypoint_statuses",
79  "Original waypoint_statuses to mark waypoint status from"),
80  BT::OutputPort<std::vector<nav2_msgs::msg::WaypointStatus>>("output_waypoint_statuses",
81  "Waypoint_statuses with in-collision waypoints marked")
82  });
83  }
84 
85 private:
86  bool use_footprint_;
87  bool consider_unknown_as_obstacle_;
88  double cost_threshold_;
89  nav_msgs::msg::Goals input_goals_;
90 };
91 
92 } // namespace nav2_behavior_tree
93 
94 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__REMOVE_IN_COLLISION_GOALS_ACTION_HPP_
Abstract class representing a service based BT node.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtServiceNode that accepts parameters must provide a providedPorts method and call pr...
A nav2_behavior_tree::BtServiceNode class that removes goals that are in collision in on the global c...
void on_tick() override
The main override required by a BT service.
RemoveInCollisionGoals(const std::string &service_node_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::RemoveInCollisionGoals.