Nav2 Navigation Stack - rolling  main
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<nav2::LifecycleNode::SharedPtr>("node");
30  client_ =
31  node_->create_client<nav2_msgs::srv::IsPathValid>(
32  "is_path_valid",
33  false /* Does not create and spin an internal executor*/);
34 
35  server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
36 }
37 
39 {
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_);
43 }
44 
46 {
47  if (!BT::isStatusActive(status())) {
48  initialize();
49  }
50 
51  nav_msgs::msg::Path path;
52  getInput("path", path);
53 
54  auto request = std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
55 
56  request->path = path;
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;
62  }
63  return BT::NodeStatus::FAILURE;
64 }
65 
66 } // namespace nav2_behavior_tree
67 
68 #include "behaviortree_cpp/bt_factory.h"
69 BT_REGISTER_NODES(factory)
70 {
71  factory.registerNodeType<nav2_behavior_tree::IsPathValidCondition>("IsPathValid");
72 }
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.