15 #include "nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp"
20 namespace nav2_behavior_tree
23 IsPathValidCondition::IsPathValidCondition(
24 const std::string & condition_name,
25 const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf),
27 max_cost_(254), consider_unknown_as_obstacle_(false)
29 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
31 node_->create_client<nav2_msgs::srv::IsPathValid>(
35 server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>(
"server_timeout");
40 getInput<std::chrono::milliseconds>(
"server_timeout", server_timeout_);
41 getInput<unsigned int>(
"max_cost", max_cost_);
42 getInput<bool>(
"consider_unknown_as_obstacle", consider_unknown_as_obstacle_);
47 if (!BT::isStatusActive(status())) {
51 nav_msgs::msg::Path path;
52 getInput(
"path", path);
54 auto request = std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
57 request->max_cost = max_cost_;
58 request->consider_unknown_as_obstacle = consider_unknown_as_obstacle_;
59 auto response = client_->
invoke(request, server_timeout_);
60 if (response->is_valid) {
61 return BT::NodeStatus::SUCCESS;
63 return BT::NodeStatus::FAILURE;
68 #include "behaviortree_cpp/bt_factory.h"
69 BT_REGISTER_NODES(factory)
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1), const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed or timed out.
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.