18 #include "nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp"
20 using namespace std::chrono_literals;
22 namespace nav2_behavior_tree
25 IsStuckCondition::IsStuckCondition(
26 const std::string & condition_name,
27 const BT::NodeConfiguration & conf)
28 : BT::ConditionNode(condition_name, conf),
30 odom_history_size_(10),
32 brake_accel_limit_(-10.0)
34 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
35 callback_group_ = node_->create_callback_group(
36 rclcpp::CallbackGroupType::MutuallyExclusive,
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();});
41 rclcpp::SubscriptionOptions sub_option;
42 sub_option.callback_group = callback_group_;
43 odom_sub_ = node_->create_subscription<nav_msgs::msg::Odometry>(
45 rclcpp::SystemDefaultsQoS(),
49 RCLCPP_DEBUG(node_->get_logger(),
"Initialized an IsStuckCondition BT node");
51 RCLCPP_INFO_ONCE(node_->get_logger(),
"Waiting on odometry");
56 RCLCPP_DEBUG(node_->get_logger(),
"Shutting down IsStuckCondition BT node");
57 callback_group_executor_.cancel();
58 callback_group_executor_thread.join();
63 RCLCPP_INFO_ONCE(node_->get_logger(),
"Got odometry");
65 while (odom_history_.size() >= odom_history_size_) {
66 odom_history_.pop_front();
69 odom_history_.push_back(*msg);
83 return BT::NodeStatus::SUCCESS;
87 return BT::NodeStatus::FAILURE;
92 static std::string prev_msg;
94 if (msg == prev_msg) {
98 RCLCPP_INFO(node_->get_logger(),
"%s", msg.c_str());
106 if (odom_history_.size() > 2) {
107 auto curr_odom = odom_history_.end()[-1];
108 double curr_time =
static_cast<double>(curr_odom.header.stamp.sec);
109 curr_time += (
static_cast<double>(curr_odom.header.stamp.nanosec)) * 1e-9;
111 auto prev_odom = odom_history_.end()[-2];
112 double prev_time =
static_cast<double>(prev_odom.header.stamp.sec);
113 prev_time += (
static_cast<double>(prev_odom.header.stamp.nanosec)) * 1e-9;
115 double dt = curr_time - prev_time;
116 double vel_diff =
static_cast<double>(
117 curr_odom.twist.twist.linear.x - prev_odom.twist.twist.linear.x);
118 current_accel_ = vel_diff / dt;
133 if (current_accel_ < brake_accel_limit_) {
135 node_->get_logger(),
"Current deceleration is beyond brake limit."
136 " brake limit: %.2f, current accel: %.2f", brake_accel_limit_, current_accel_);
146 #include "behaviortree_cpp/bt_factory.h"
147 BT_REGISTER_NODES(factory)
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.