16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__DISTANCE_TRAVELED_CONDITION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__DISTANCE_TRAVELED_CONDITION_HPP_
22 #include "behaviortree_cpp/condition_node.h"
24 #include "rclcpp/rclcpp.hpp"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "tf2_ros/buffer.h"
27 #include "nav2_behavior_tree/bt_utils.hpp"
29 namespace nav2_behavior_tree
47 const std::string & condition_name,
48 const BT::NodeConfiguration & conf);
56 BT::NodeStatus
tick()
override;
70 BT::InputPort<double>(
"distance", 1.0,
"Distance"),
71 BT::InputPort<std::string>(
"global_frame",
"Global frame"),
72 BT::InputPort<std::string>(
"robot_base_frame",
"Robot base frame")
77 rclcpp::Node::SharedPtr node_;
78 std::shared_ptr<tf2_ros::Buffer> tf_;
80 geometry_msgs::msg::PoseStamped start_pose_;
83 double transform_tolerance_;
84 std::string global_frame_, robot_base_frame_;
A BT::ConditionNode that returns SUCCESS every time the robot travels a specified distance and FAILUR...
BT::NodeStatus tick() override
The main override required by a BT action.
static BT::PortsList providedPorts()
Creates list of BT ports.
void initialize()
Function to read parameters and initialize class variables.