Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
is_pose_occupied_condition.cpp
1 // Copyright (c) 2025 Maurice Alexander Purnawan
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 "nav2_behavior_tree/plugins/condition/is_pose_occupied_condition.hpp"
16 #include <chrono>
17 #include <memory>
18 #include <string>
19 
20 namespace nav2_behavior_tree
21 {
22 
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")
29 {
30  node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
31  server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
32 }
33 
35 {
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_);
41  client_ =
42  node_->create_client<nav2_msgs::srv::GetCosts>(
43  service_name_,
44  false /* Does not create and spin an internal executor*/);
45 }
46 
48 {
49  if (!BT::isStatusActive(status())) {
50  initialize();
51  }
52  geometry_msgs::msg::PoseStamped pose;
53  getInput("pose", pose);
54 
55  auto request = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
56  request->use_footprint = use_footprint_;
57  request->poses.push_back(pose);
58 
59  auto response = client_->invoke(request, server_timeout_);
60 
61  if(!response->success) {
62  RCLCPP_ERROR(
63  node_->get_logger(),
64  "GetCosts service call failed");
65  return BT::NodeStatus::FAILURE;
66  }
67 
68  if((response->costs[0] == 255 && !consider_unknown_as_obstacle_) ||
69  response->costs[0] < cost_threshold_)
70  {
71  return BT::NodeStatus::FAILURE;
72  } else {
73  return BT::NodeStatus::SUCCESS;
74  }
75 }
76 
77 } // namespace nav2_behavior_tree
78 
79 #include "behaviortree_cpp/bt_factory.h"
80 BT_REGISTER_NODES(factory)
81 {
82  factory.registerNodeType<nav2_behavior_tree::IsPoseOccupiedCondition>("IsPoseOccupied");
83 }
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.