18 #include "nav2_behavior_tree/plugins/condition/is_stopped_condition.hpp"
20 namespace nav2_behavior_tree
23 IsStoppedCondition::IsStoppedCondition(
24 const std::string & condition_name,
25 const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf),
27 velocity_threshold_(0.01),
28 duration_stopped_(1000ms),
29 stopped_stamp_(rclcpp::Time(0, 0, RCL_ROS_TIME))
31 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
32 odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
38 RCLCPP_DEBUG(node_->get_logger(),
"Shutting down IsStoppedCondition BT node");
43 getInput(
"velocity_threshold", velocity_threshold_);
44 getInput(
"duration_stopped", duration_stopped_);
46 auto twist = odom_smoother_->getRawTwistStamped();
49 if (twist.header.stamp.sec == 0 && twist.header.stamp.nanosec == 0) {
50 twist.header.stamp = node_->get_clock()->now();
53 if (abs(twist.twist.linear.x) < velocity_threshold_ &&
54 abs(twist.twist.linear.y) < velocity_threshold_ &&
55 abs(twist.twist.angular.z) < velocity_threshold_)
57 if (stopped_stamp_ == rclcpp::Time(0, 0, RCL_ROS_TIME)) {
58 stopped_stamp_ = rclcpp::Time(twist.header.stamp);
61 if (node_->get_clock()->now() - stopped_stamp_ > rclcpp::Duration(duration_stopped_)) {
62 stopped_stamp_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
63 return BT::NodeStatus::SUCCESS;
65 return BT::NodeStatus::RUNNING;
69 stopped_stamp_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
70 return BT::NodeStatus::FAILURE;
76 #include "behaviortree_cpp/bt_factory.h"
77 BT_REGISTER_NODES(factory)
A BT::ConditionNode that tracks robot odometry and returns SUCCESS if robot is considered stopped for...
~IsStoppedCondition() override
A destructor for nav2_behavior_tree::IsStoppedCondition.
BT::NodeStatus tick() override
The main override required by a BT action.