Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
is_stuck_condition.hpp
1 // Copyright (c) 2018 Intel Corporation
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_STUCK_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STUCK_CONDITION_HPP_
17 
18 #include <string>
19 #include <atomic>
20 #include <deque>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "behaviortree_cpp/condition_node.h"
24 #include "nav_msgs/msg/odometry.hpp"
25 
26 namespace nav2_behavior_tree
27 {
28 
33 class IsStuckCondition : public BT::ConditionNode
34 {
35 public:
42  const std::string & condition_name,
43  const BT::NodeConfiguration & conf);
44 
45  IsStuckCondition() = delete;
46 
50  ~IsStuckCondition() override;
51 
56  void onOdomReceived(const typename nav_msgs::msg::Odometry::SharedPtr msg);
57 
62  BT::NodeStatus tick() override;
63 
67  void logStuck(const std::string & msg) const;
68 
72  void updateStates();
73 
78  bool isStuck();
79 
84  static BT::PortsList providedPorts() {return {};}
85 
86 private:
87  // The node that will be used for any ROS operations
88  rclcpp::Node::SharedPtr node_;
89  rclcpp::CallbackGroup::SharedPtr callback_group_;
90  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
91  std::thread callback_group_executor_thread;
92 
93  std::atomic<bool> is_stuck_;
94 
95  // Listen to odometry
96  rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
97  // Store history of odometry measurements
98  std::deque<nav_msgs::msg::Odometry> odom_history_;
99  std::deque<nav_msgs::msg::Odometry>::size_type odom_history_size_;
100 
101  // Calculated states
102  double current_accel_;
103 
104  // Robot specific parameters
105  double brake_accel_limit_;
106 };
107 
108 } // namespace nav2_behavior_tree
109 
110 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STUCK_CONDITION_HPP_
A BT::ConditionNode that tracks robot odometry and returns SUCCESS if robot is stuck somewhere and FA...
void updateStates()
Function to approximate acceleration from the odom history.
static BT::PortsList providedPorts()
Creates list of BT ports.
bool isStuck()
Detect if robot bumped into something by checking for abnormal deceleration.
void onOdomReceived(const typename nav_msgs::msg::Odometry::SharedPtr msg)
Callback function for odom topic.
~IsStuckCondition() override
A destructor for nav2_behavior_tree::IsStuckCondition.
BT::NodeStatus tick() override
The main override required by a BT action.
void logStuck(const std::string &msg) const
Function to log status when robot is stuck/free.