15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_POSE_OCCUPIED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_POSE_OCCUPIED_CONDITION_HPP_
21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "behaviortree_cpp/condition_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_msgs/srv/get_costs.hpp"
26 #include "nav2_ros_common/service_client.hpp"
27 #include "nav2_behavior_tree/bt_utils.hpp"
28 #include "nav2_behavior_tree/json_utils.hpp"
31 namespace nav2_behavior_tree
47 const std::string & condition_name,
48 const BT::NodeConfiguration & conf);
56 BT::NodeStatus
tick()
override;
70 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
71 BT::RegisterJsonDefinition<std::chrono::milliseconds>();
74 BT::InputPort<geometry_msgs::msg::PoseStamped>(
"pose",
"Pose to check if occupied"),
75 BT::InputPort<std::string>(
"service_name",
"global_costmap/get_cost_global_costmap"),
76 BT::InputPort<double>(
77 "cost_threshold", 254.0,
78 "Cost threshold for considering a pose occupied"),
79 BT::InputPort<bool>(
"use_footprint",
true,
"Whether to use footprint cost"),
81 "consider_unknown_as_obstacle",
false,
82 "Whether to consider unknown cost as obstacle"),
83 BT::InputPort<std::chrono::milliseconds>(
"server_timeout"),
88 nav2::LifecycleNode::SharedPtr node_;
89 nav2::ServiceClient<nav2_msgs::srv::GetCosts>::SharedPtr client_;
92 std::chrono::milliseconds server_timeout_;
94 bool consider_unknown_as_obstacle_;
95 double cost_threshold_;
96 std::string service_name_;
A BT::ConditionNode that returns SUCCESS when the IsPoseOccupied service returns true and FAILURE oth...
void initialize()
Function to read parameters and initialize class variables.
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus tick() override
The main override required by a BT action.