15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_PATH_VALID_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_PATH_VALID_CONDITION_HPP_
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"
26 namespace nav2_behavior_tree
42 const std::string & condition_name,
43 const BT::NodeConfiguration & conf);
51 BT::NodeStatus
tick()
override;
65 BT::InputPort<nav_msgs::msg::Path>(
"path",
"Path to Check"),
66 BT::InputPort<std::chrono::milliseconds>(
"server_timeout")
71 rclcpp::Node::SharedPtr node_;
72 rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
75 std::chrono::milliseconds server_timeout_;
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.