Nav2 Navigation Stack - jazzy  jazzy
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 "geometry_msgs/msg/pose_stamped.hpp"
24 #include "nav2_msgs/srv/is_path_valid.hpp"
25 
26 namespace nav2_behavior_tree
27 {
28 
33 class IsPathValidCondition : public BT::ConditionNode
34 {
35 public:
42  const std::string & condition_name,
43  const BT::NodeConfiguration & conf);
44 
45  IsPathValidCondition() = delete;
46 
51  BT::NodeStatus tick() override;
52 
56  void initialize();
57 
62  static BT::PortsList providedPorts()
63  {
64  return {
65  BT::InputPort<nav_msgs::msg::Path>("path", "Path to Check"),
66  BT::InputPort<std::chrono::milliseconds>("server_timeout")
67  };
68  }
69 
70 private:
71  rclcpp::Node::SharedPtr node_;
72  rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
73  // The timeout value while waiting for a responce from the
74  // is path valid service
75  std::chrono::milliseconds server_timeout_;
76 };
77 
78 } // namespace nav2_behavior_tree
79 
80 #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.