15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_
21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "behaviortree_cpp/condition_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "nav_msgs/msg/odometry.hpp"
25 #include "nav2_util/odometry_utils.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
30 using namespace std::chrono_literals;
32 namespace nav2_behavior_tree
48 const std::string & condition_name,
49 const BT::NodeConfiguration & conf);
62 BT::NodeStatus tick()
override;
71 BT::RegisterJsonDefinition<std::chrono::milliseconds>();
74 BT::InputPort<double>(
"velocity_threshold", 0.01,
75 "Velocity threshold below which robot is considered stopped"),
76 BT::InputPort<std::chrono::milliseconds>(
"duration_stopped", 1000ms,
77 "Duration (ms) the velocity must remain below the threshold"),
82 nav2::LifecycleNode::SharedPtr node_;
84 double velocity_threshold_;
85 std::chrono::milliseconds duration_stopped_;
86 rclcpp::Time stopped_stamp_;
88 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
A BT::ConditionNode that tracks robot odometry and returns SUCCESS if robot is considered stopped for...
static BT::PortsList providedPorts()
Creates list of BT ports.