Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
is_stopped_condition.hpp
1 // Copyright (c) 2024 Angsa Robotics
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__CONDITION__IS_STOPPED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "behaviortree_cpp/condition_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "nav_msgs/msg/odometry.hpp"
25 #include "nav2_util/odometry_utils.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 
29 
30 using namespace std::chrono_literals; // NOLINT
31 
32 namespace nav2_behavior_tree
33 {
34 
39 class IsStoppedCondition : public BT::ConditionNode
40 {
41 public:
48  const std::string & condition_name,
49  const BT::NodeConfiguration & conf);
50 
51  IsStoppedCondition() = delete;
52 
56  ~IsStoppedCondition() override;
57 
62  BT::NodeStatus tick() override;
63 
68  static BT::PortsList providedPorts()
69  {
70  // Register JSON definitions for the types used in the ports
71  BT::RegisterJsonDefinition<std::chrono::milliseconds>();
72 
73  return {
74  BT::InputPort<double>("velocity_threshold", 0.01,
75  "Velocity threshold below which robot is considered stopped"),
76  BT::InputPort<std::chrono::milliseconds>("duration_stopped", 1000ms,
77  "Duration (ms) the velocity must remain below the threshold"),
78  };
79  }
80 
81 private:
82  rclcpp::Node::SharedPtr node_;
83 
84  double velocity_threshold_;
85  std::chrono::milliseconds duration_stopped_;
86  rclcpp::Time stopped_stamp_;
87 
88  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
89 };
90 
91 } // namespace nav2_behavior_tree
92 
93 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_
A BT::ConditionNode that tracks robot odometry and returns SUCCESS if robot is considered stopped for...
static BT::PortsList providedPorts()
Creates list of BT ports.