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_
22 #include "rclcpp/rclcpp.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"
28 namespace nav2_behavior_tree
46 const std::string & service_node_name,
47 const BT::NodeConfiguration & conf);
55 BT::NodeStatus on_completion(std::shared_ptr<nav2_msgs::srv::GetCosts::Response> response)
58 static BT::PortsList providedPorts()
61 BT::RegisterJsonDefinition<nav_msgs::msg::Goals>();
62 BT::RegisterJsonDefinition<nav2_msgs::msg::WaypointStatus>();
63 BT::RegisterJsonDefinition<std::vector<nav2_msgs::msg::WaypointStatus>>();
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"),
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")
87 bool consider_unknown_as_obstacle_;
88 double cost_threshold_;
89 nav_msgs::msg::Goals input_goals_;
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.