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_v3/condition_node.h"
24 #include "rclcpp/rclcpp.hpp"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "tf2_ros/buffer.h"
28 namespace nav2_behavior_tree
44 const std::string & condition_name,
45 const BT::NodeConfiguration & conf);
53 BT::NodeStatus
tick()
override;
62 BT::InputPort<double>(
"distance", 1.0,
"Distance"),
63 BT::InputPort<std::string>(
"global_frame", std::string(
"map"),
"Global frame"),
64 BT::InputPort<std::string>(
"robot_base_frame", std::string(
"base_link"),
"Robot base frame")
69 rclcpp::Node::SharedPtr node_;
70 std::shared_ptr<tf2_ros::Buffer> tf_;
72 geometry_msgs::msg::PoseStamped start_pose_;
75 double transform_tolerance_;
76 std::string global_frame_;
77 std::string 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.