15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STUCK_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STUCK_CONDITION_HPP_
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 #include "behaviortree_cpp/condition_node.h"
24 #include "nav_msgs/msg/odometry.hpp"
26 namespace nav2_behavior_tree
42 const std::string & condition_name,
43 const BT::NodeConfiguration & conf);
56 void onOdomReceived(
const typename nav_msgs::msg::Odometry::SharedPtr msg);
62 BT::NodeStatus
tick()
override;
67 void logStuck(
const std::string & msg)
const;
88 nav2::LifecycleNode::SharedPtr node_;
89 rclcpp::CallbackGroup::SharedPtr callback_group_;
90 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
91 std::thread callback_group_executor_thread;
93 std::atomic<bool> is_stuck_;
96 nav2::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
98 std::deque<nav_msgs::msg::Odometry> odom_history_;
99 std::deque<nav_msgs::msg::Odometry>::size_type odom_history_size_;
102 double current_accel_;
105 double brake_accel_limit_;
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.