Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
is_path_valid_condition.cpp
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 #include "nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp"
16 #include <chrono>
17 #include <memory>
18 #include <string>
19 
20 namespace nav2_behavior_tree
21 {
22 
23 IsPathValidCondition::IsPathValidCondition(
24  const std::string & condition_name,
25  const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf)
27 {
28  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
29  client_ = node_->create_client<nav2_msgs::srv::IsPathValid>("is_path_valid");
30 
31  server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
32 }
33 
35 {
36  getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
37 }
38 
40 {
41  if (!BT::isStatusActive(status())) {
42  initialize();
43  }
44 
45  nav_msgs::msg::Path path;
46  getInput("path", path);
47 
48  auto request = std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
49 
50  request->path = path;
51  auto result = client_->async_send_request(request);
52 
53  if (rclcpp::spin_until_future_complete(node_, result, server_timeout_) ==
54  rclcpp::FutureReturnCode::SUCCESS)
55  {
56  if (result.get()->is_valid) {
57  return BT::NodeStatus::SUCCESS;
58  }
59  }
60  return BT::NodeStatus::FAILURE;
61 }
62 
63 } // namespace nav2_behavior_tree
64 
65 #include "behaviortree_cpp/bt_factory.h"
66 BT_REGISTER_NODES(factory)
67 {
68  factory.registerNodeType<nav2_behavior_tree::IsPathValidCondition>("IsPathValid");
69 }
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.