15 #include "nav2_behavior_tree/plugins/condition/is_pose_occupied_condition.hpp"
20 namespace nav2_behavior_tree
23 IsPoseOccupiedCondition::IsPoseOccupiedCondition(
24 const std::string & condition_name,
25 const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf),
27 use_footprint_(true), consider_unknown_as_obstacle_(false), cost_threshold_(254),
28 service_name_(
"global_costmap/get_cost_global_costmap")
30 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
31 server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>(
"server_timeout");
36 getInput<std::string>(
"service_name", service_name_);
37 getInput<double>(
"cost_threshold", cost_threshold_);
38 getInput<bool>(
"use_footprint", use_footprint_);
39 getInput<bool>(
"consider_unknown_as_obstacle", consider_unknown_as_obstacle_);
40 getInput<std::chrono::milliseconds>(
"server_timeout", server_timeout_);
42 node_->create_client<nav2_msgs::srv::GetCosts>(
49 if (!BT::isStatusActive(status())) {
52 geometry_msgs::msg::PoseStamped pose;
53 getInput(
"pose", pose);
55 auto request = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
56 request->use_footprint = use_footprint_;
57 request->poses.push_back(pose);
59 auto response = client_->
invoke(request, server_timeout_);
61 if(!response->success) {
64 "GetCosts service call failed");
65 return BT::NodeStatus::FAILURE;
68 if((response->costs[0] == 255 && !consider_unknown_as_obstacle_) ||
69 response->costs[0] < cost_threshold_)
71 return BT::NodeStatus::FAILURE;
73 return BT::NodeStatus::SUCCESS;
79 #include "behaviortree_cpp/bt_factory.h"
80 BT_REGISTER_NODES(factory)
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1), const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed or timed out.
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.
BT::NodeStatus tick() override
The main override required by a BT action.