|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A BT::ConditionNode that tracks robot odometry and returns SUCCESS if robot is stuck somewhere and FAILURE otherwise. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp>


Public Member Functions | |
| IsStuckCondition (const std::string &condition_name, const BT::NodeConfiguration &conf) | |
| A constructor for nav2_behavior_tree::IsStuckCondition. More... | |
| ~IsStuckCondition () override | |
| A destructor for nav2_behavior_tree::IsStuckCondition. | |
| void | onOdomReceived (const typename nav_msgs::msg::Odometry::SharedPtr msg) |
| Callback function for odom topic. More... | |
| BT::NodeStatus | tick () override |
| The main override required by a BT action. More... | |
| void | logStuck (const std::string &msg) const |
| Function to log status when robot is stuck/free. | |
| void | updateStates () |
| Function to approximate acceleration from the odom history. | |
| bool | isStuck () |
| Detect if robot bumped into something by checking for abnormal deceleration. More... | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| Creates list of BT ports. More... | |
A BT::ConditionNode that tracks robot odometry and returns SUCCESS if robot is stuck somewhere and FAILURE otherwise.
Definition at line 33 of file is_stuck_condition.hpp.
| nav2_behavior_tree::IsStuckCondition::IsStuckCondition | ( | const std::string & | condition_name, |
| const BT::NodeConfiguration & | conf | ||
| ) |
A constructor for nav2_behavior_tree::IsStuckCondition.
| condition_name | Name for the XML tag for this node |
| conf | BT node configuration |
Definition at line 25 of file is_stuck_condition.cpp.
References onOdomReceived().

| bool nav2_behavior_tree::IsStuckCondition::isStuck | ( | ) |
Detect if robot bumped into something by checking for abnormal deceleration.
Definition at line 124 of file is_stuck_condition.cpp.
Referenced by updateStates().

| void nav2_behavior_tree::IsStuckCondition::onOdomReceived | ( | const typename nav_msgs::msg::Odometry::SharedPtr | msg | ) |
Callback function for odom topic.
| msg | Shared pointer to nav_msgs::msg::Odometry::SharedPtr message |
Definition at line 61 of file is_stuck_condition.cpp.
References updateStates().
Referenced by IsStuckCondition().


|
inlinestatic |
Creates list of BT ports.
Definition at line 84 of file is_stuck_condition.hpp.
|
override |
The main override required by a BT action.
Definition at line 75 of file is_stuck_condition.cpp.
References logStuck().
