Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
is_path_valid_condition.hpp
1 // Copyright (c) 2021 Joshua Wallace
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_PATH_VALID_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_PATH_VALID_CONDITION_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.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/is_path_valid.hpp"
26 #include "nav2_util/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 IsPathValidCondition : public BT::ConditionNode
39 {
40 public:
47  const std::string & condition_name,
48  const BT::NodeConfiguration & conf);
49 
50  IsPathValidCondition() = 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<nav_msgs::msg::Path>();
71  BT::RegisterJsonDefinition<std::chrono::milliseconds>();
72 
73  return {
74  BT::InputPort<nav_msgs::msg::Path>("path", "Path to Check"),
75  BT::InputPort<std::chrono::milliseconds>("server_timeout"),
76  BT::InputPort<unsigned int>("max_cost", 253, "Maximum cost of the path"),
77  BT::InputPort<bool>(
78  "consider_unknown_as_obstacle", false,
79  "Whether to consider unknown cost as obstacle")
80  };
81  }
82 
83 private:
84  rclcpp::Node::SharedPtr node_;
85  nav2_util::ServiceClient<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
86  // The timeout value while waiting for a response from the
87  // is path valid service
88  std::chrono::milliseconds server_timeout_;
89  unsigned int max_cost_;
90  bool consider_unknown_as_obstacle_;
91 };
92 
93 } // namespace nav2_behavior_tree
94 
95 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_PATH_VALID_CONDITION_HPP_
A BT::ConditionNode that returns SUCCESS when the IsPathValid service returns true and FAILURE otherw...
void initialize()
Function to read parameters and initialize class variables.
BT::NodeStatus tick() override
The main override required by a BT action.
static BT::PortsList providedPorts()
Creates list of BT ports.