Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
is_stuck_condition.cpp
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 #include <string>
16 #include <chrono>
17 
18 #include "nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp"
19 
20 using namespace std::chrono_literals; // NOLINT
21 
22 namespace nav2_behavior_tree
23 {
24 
25 IsStuckCondition::IsStuckCondition(
26  const std::string & condition_name,
27  const BT::NodeConfiguration & conf)
28 : BT::ConditionNode(condition_name, conf),
29  is_stuck_(false),
30  odom_history_size_(10),
31  current_accel_(0.0),
32  brake_accel_limit_(-10.0)
33 {
34  node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
35  callback_group_ = node_->create_callback_group(
36  rclcpp::CallbackGroupType::MutuallyExclusive,
37  false);
38  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
39  callback_group_executor_thread = std::thread([this]() {callback_group_executor_.spin();});
40 
41  odom_sub_ = node_->create_subscription<nav_msgs::msg::Odometry>(
42  "odom",
43  std::bind(&IsStuckCondition::onOdomReceived, this, std::placeholders::_1),
45  callback_group_);
46 
47  RCLCPP_DEBUG(node_->get_logger(), "Initialized an IsStuckCondition BT node");
48 
49  RCLCPP_INFO_ONCE(node_->get_logger(), "Waiting on odometry");
50 }
51 
53 {
54  RCLCPP_DEBUG(node_->get_logger(), "Shutting down IsStuckCondition BT node");
55  callback_group_executor_.cancel();
56  callback_group_executor_thread.join();
57 }
58 
59 void IsStuckCondition::onOdomReceived(const typename nav_msgs::msg::Odometry::SharedPtr msg)
60 {
61  RCLCPP_INFO_ONCE(node_->get_logger(), "Got odometry");
62 
63  while (odom_history_.size() >= odom_history_size_) {
64  odom_history_.pop_front();
65  }
66 
67  odom_history_.push_back(*msg);
68 
69  // TODO(orduno) #383 Move the state calculation and is stuck to robot class
70  updateStates();
71 }
72 
73 BT::NodeStatus IsStuckCondition::tick()
74 {
75  // TODO(orduno) #383 Once check for is stuck and state calculations are moved to robot class
76  // this becomes
77  // if (robot_state_.isStuck()) {
78 
79  if (is_stuck_) {
80  logStuck("Robot got stuck!");
81  return BT::NodeStatus::SUCCESS; // Successfully detected a stuck condition
82  }
83 
84  logStuck("Robot is free");
85  return BT::NodeStatus::FAILURE; // Failed to detected a stuck condition
86 }
87 
88 void IsStuckCondition::logStuck(const std::string & msg) const
89 {
90  static std::string prev_msg;
91 
92  if (msg == prev_msg) {
93  return;
94  }
95 
96  RCLCPP_INFO(node_->get_logger(), "%s", msg.c_str());
97  prev_msg = msg;
98 }
99 
101 {
102  // Approximate acceleration
103  // TODO(orduno) #400 Smooth out velocity history for better accel approx.
104  if (odom_history_.size() > 2) {
105  auto curr_odom = odom_history_.end()[-1];
106  double curr_time = static_cast<double>(curr_odom.header.stamp.sec);
107  curr_time += (static_cast<double>(curr_odom.header.stamp.nanosec)) * 1e-9;
108 
109  auto prev_odom = odom_history_.end()[-2];
110  double prev_time = static_cast<double>(prev_odom.header.stamp.sec);
111  prev_time += (static_cast<double>(prev_odom.header.stamp.nanosec)) * 1e-9;
112 
113  double dt = curr_time - prev_time;
114  double vel_diff = static_cast<double>(
115  curr_odom.twist.twist.linear.x - prev_odom.twist.twist.linear.x);
116  current_accel_ = vel_diff / dt;
117  }
118 
119  is_stuck_ = isStuck();
120 }
121 
123 {
124  // TODO(orduno) #400 The robot getting stuck can result on different types of motion
125  // depending on the state prior to getting stuck (sudden change in accel, not moving at all,
126  // random oscillations, etc). For now, we only address the case where there is a sudden
127  // harsh deceleration. A better approach to capture all situations would be to do a forward
128  // simulation of the robot motion and compare it with the actual one.
129 
130  // Detect if robot bumped into something by checking for abnormal deceleration
131  if (current_accel_ < brake_accel_limit_) {
132  RCLCPP_DEBUG(
133  node_->get_logger(), "Current deceleration is beyond brake limit."
134  " brake limit: %.2f, current accel: %.2f", brake_accel_limit_, current_accel_);
135 
136  return true;
137  }
138 
139  return false;
140 }
141 
142 } // namespace nav2_behavior_tree
143 
144 #include "behaviortree_cpp/bt_factory.h"
145 BT_REGISTER_NODES(factory)
146 {
147  factory.registerNodeType<nav2_behavior_tree::IsStuckCondition>("IsStuck");
148 }
A QoS profile for standard reliable topics with a history of 10 messages.
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.
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.