Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
is_pose_occupied_condition.hpp
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_POSE_OCCUPIED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_POSE_OCCUPIED_CONDITION_HPP_
17 
18 #include <string>
19 #include <memory>
20 
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"
29 
30 
31 namespace nav2_behavior_tree
32 {
33 
38 class IsPoseOccupiedCondition : public BT::ConditionNode
39 {
40 public:
47  const std::string & condition_name,
48  const BT::NodeConfiguration & conf);
49 
50  IsPoseOccupiedCondition() = delete;
51 
56  BT::NodeStatus tick() override;
57 
61  void initialize();
62 
67  static BT::PortsList providedPorts()
68  {
69  // Register JSON definitions for the types used in the ports
70  BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
71  BT::RegisterJsonDefinition<std::chrono::milliseconds>();
72 
73  return {
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"),
80  BT::InputPort<bool>(
81  "consider_unknown_as_obstacle", false,
82  "Whether to consider unknown cost as obstacle"),
83  BT::InputPort<std::chrono::milliseconds>("server_timeout"),
84  };
85  }
86 
87 private:
88  nav2::LifecycleNode::SharedPtr node_;
89  nav2::ServiceClient<nav2_msgs::srv::GetCosts>::SharedPtr client_;
90  // The timeout value while waiting for a response from the
91  // get cost service
92  std::chrono::milliseconds server_timeout_;
93  bool use_footprint_;
94  bool consider_unknown_as_obstacle_;
95  double cost_threshold_;
96  std::string service_name_;
97 };
98 
99 } // namespace nav2_behavior_tree
100 
101 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_POSE_OCCUPIED_CONDITION_HPP_
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.