19 #include "nav2_util/robot_utils.hpp"
20 #include "nav2_util/geometry_utils.hpp"
22 #include "nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp"
24 namespace nav2_behavior_tree
27 DistanceTraveledCondition::DistanceTraveledCondition(
28 const std::string & condition_name,
29 const BT::NodeConfiguration & conf)
30 : BT::ConditionNode(condition_name, conf),
32 transform_tolerance_(0.1),
34 robot_base_frame_(
"base_link")
36 getInput(
"distance", distance_);
37 getInput(
"global_frame", global_frame_);
38 getInput(
"robot_base_frame", robot_base_frame_);
39 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
40 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
41 node_->get_parameter(
"transform_tolerance", transform_tolerance_);
46 if (status() == BT::NodeStatus::IDLE) {
47 if (!nav2_util::getCurrentPose(
48 start_pose_, *tf_, global_frame_, robot_base_frame_,
49 transform_tolerance_))
51 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
53 return BT::NodeStatus::FAILURE;
57 geometry_msgs::msg::PoseStamped current_pose;
58 if (!nav2_util::getCurrentPose(
59 current_pose, *tf_, global_frame_, robot_base_frame_,
60 transform_tolerance_))
62 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
63 return BT::NodeStatus::FAILURE;
67 auto travelled = nav2_util::geometry_utils::euclidean_distance(
68 start_pose_.pose, current_pose.pose);
70 if (travelled < distance_) {
71 return BT::NodeStatus::FAILURE;
75 start_pose_ = current_pose;
77 return BT::NodeStatus::SUCCESS;
82 #include "behaviortree_cpp_v3/bt_factory.h"
83 BT_REGISTER_NODES(factory)
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.