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)
38 getInput(
"distance", distance_);
40 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
41 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
42 node_->get_parameter(
"transform_tolerance", transform_tolerance_);
44 global_frame_ = BT::deconflictPortAndParamFrame<std::string>(
45 node_,
"global_frame",
this);
46 robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
47 node_,
"robot_base_frame",
this);
52 if (!BT::isStatusActive(status())) {
56 if (!BT::isStatusActive(status())) {
57 if (!nav2_util::getCurrentPose(
58 start_pose_, *tf_, global_frame_, robot_base_frame_,
59 transform_tolerance_))
61 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
63 return BT::NodeStatus::FAILURE;
67 geometry_msgs::msg::PoseStamped current_pose;
68 if (!nav2_util::getCurrentPose(
69 current_pose, *tf_, global_frame_, robot_base_frame_,
70 transform_tolerance_))
72 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
73 return BT::NodeStatus::FAILURE;
77 auto travelled = nav2_util::geometry_utils::euclidean_distance(
78 start_pose_.pose, current_pose.pose);
80 if (travelled < distance_) {
81 return BT::NodeStatus::FAILURE;
85 start_pose_ = current_pose;
87 return BT::NodeStatus::SUCCESS;
92 #include "behaviortree_cpp/bt_factory.h"
93 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.
void initialize()
Function to read parameters and initialize class variables.