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 "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/is_path_valid.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"
31 namespace nav2_behavior_tree
47 const std::string & condition_name,
48 const BT::NodeConfiguration & conf);
56 BT::NodeStatus
tick()
override;
70 BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
71 BT::RegisterJsonDefinition<std::chrono::milliseconds>();
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"),
78 "consider_unknown_as_obstacle",
false,
79 "Whether to consider unknown cost as obstacle")
84 nav2::LifecycleNode::SharedPtr node_;
85 nav2::ServiceClient<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
88 std::chrono::milliseconds server_timeout_;
89 unsigned int max_cost_;
90 bool consider_unknown_as_obstacle_;
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.