Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
path_longer_on_approach.hpp
1 // Copyright (c) 2022 Neobotix GmbH
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__PATH_LONGER_ON_APPROACH_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__PATH_LONGER_ON_APPROACH_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <limits>
21 
22 #include "behaviortree_cpp/decorator_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav_msgs/msg/path.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 #include "rclcpp/rclcpp.hpp"
29 
30 namespace nav2_behavior_tree
31 {
32 
37 class PathLongerOnApproach : public BT::DecoratorNode
38 {
39 public:
46  const std::string & name,
47  const BT::NodeConfiguration & conf);
48 
53  static BT::PortsList providedPorts()
54  {
55  // Register JSON definitions for the types used in the ports
56  BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
57 
58  return {
59  BT::InputPort<nav_msgs::msg::Path>("path", "Planned Path"),
60  BT::InputPort<double>(
61  "prox_len", 3.0,
62  "Proximity length (m) for the path to be longer on approach"),
63  BT::InputPort<double>(
64  "length_factor", 2.0,
65  "Length multiplication factor to check if the path is significantly longer"),
66  };
67  }
68 
73  BT::NodeStatus tick() override;
74 
75 private:
82  bool isPathUpdated(
83  nav_msgs::msg::Path & new_path,
84  nav_msgs::msg::Path & old_path);
85 
92  bool isRobotInGoalProximity(
93  nav_msgs::msg::Path & old_path,
94  double & prox_leng);
95 
103  bool isNewPathLonger(
104  nav_msgs::msg::Path & new_path,
105  nav_msgs::msg::Path & old_path,
106  double & length_factor);
107 
108 private:
109  nav_msgs::msg::Path new_path_;
110  nav_msgs::msg::Path old_path_;
111  double prox_len_ = std::numeric_limits<double>::max();
112  double length_factor_ = std::numeric_limits<double>::max();
113  nav2::LifecycleNode::SharedPtr node_;
114  bool first_time_ = true;
115 };
116 
117 } // namespace nav2_behavior_tree
118 
119 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__PATH_LONGER_ON_APPROACH_HPP_
A BT::DecoratorNode that ticks its child every time when the length of the new path is smaller than t...
static BT::PortsList providedPorts()
Creates list of BT ports.
PathLongerOnApproach(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::PathLongerOnApproach.
BT::NodeStatus tick() override
The main override required by a BT action.