Nav2 Navigation Stack - kilted  kilted
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  max_cost_(254), consider_unknown_as_obstacle_(false)
28 {
29  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
30  client_ = std::make_shared<nav2_util::ServiceClient<nav2_msgs::srv::IsPathValid>>("is_path_valid",
31  node_, false /* Does not create and spin an internal executor*/);
32 
33  server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
34 }
35 
37 {
38  getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
39  getInput<unsigned int>("max_cost", max_cost_);
40  getInput<bool>("consider_unknown_as_obstacle", consider_unknown_as_obstacle_);
41 }
42 
44 {
45  if (!BT::isStatusActive(status())) {
46  initialize();
47  }
48 
49  nav_msgs::msg::Path path;
50  getInput("path", path);
51 
52  auto request = std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
53 
54  request->path = path;
55  request->max_cost = max_cost_;
56  request->consider_unknown_as_obstacle = consider_unknown_as_obstacle_;
57  auto response = client_->invoke(request, server_timeout_);
58  if (response->is_valid) {
59  return BT::NodeStatus::SUCCESS;
60  }
61  return BT::NodeStatus::FAILURE;
62 }
63 
64 } // namespace nav2_behavior_tree
65 
66 #include "behaviortree_cpp/bt_factory.h"
67 BT_REGISTER_NODES(factory)
68 {
69  factory.registerNodeType<nav2_behavior_tree::IsPathValidCondition>("IsPathValid");
70 }
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.
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Invoke the service and block until completed or timed out.