21 #include "nav2_util/robot_utils.hpp"
22 #include "nav2_util/geometry_utils.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "tf2_ros/buffer.h"
26 #include "behaviortree_cpp/decorator_node.h"
28 #include "nav2_behavior_tree/plugins/decorator/distance_controller.hpp"
30 namespace nav2_behavior_tree
34 const std::string & name,
35 const BT::NodeConfiguration & conf)
36 : BT::DecoratorNode(name, conf),
40 getInput(
"distance", distance_);
41 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
42 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
43 node_->get_parameter(
"transform_tolerance", transform_tolerance_);
45 global_frame_ = BT::deconflictPortAndParamFrame<std::string>(
46 node_,
"global_frame",
this);
47 robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
48 node_,
"robot_base_frame",
this);
51 inline BT::NodeStatus DistanceController::tick()
53 if (!BT::isStatusActive(status())) {
56 if (!nav2_util::getCurrentPose(
57 start_pose_, *tf_, global_frame_, robot_base_frame_,
58 transform_tolerance_))
60 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
61 return BT::NodeStatus::FAILURE;
66 setStatus(BT::NodeStatus::RUNNING);
69 geometry_msgs::msg::PoseStamped current_pose;
70 if (!nav2_util::getCurrentPose(
71 current_pose, *tf_, global_frame_, robot_base_frame_,
72 transform_tolerance_))
74 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
75 return BT::NodeStatus::FAILURE;
79 auto travelled = nav2_util::geometry_utils::euclidean_distance(
80 start_pose_.pose, current_pose.pose);
85 if (first_time_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
86 travelled >= distance_)
89 const BT::NodeStatus child_state = child_node_->executeTick();
91 switch (child_state) {
92 case BT::NodeStatus::SKIPPED:
93 case BT::NodeStatus::RUNNING:
96 case BT::NodeStatus::SUCCESS:
97 if (!nav2_util::getCurrentPose(
98 start_pose_, *tf_, global_frame_, robot_base_frame_,
99 transform_tolerance_))
101 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
102 return BT::NodeStatus::FAILURE;
104 return BT::NodeStatus::SUCCESS;
106 case BT::NodeStatus::FAILURE:
108 return BT::NodeStatus::FAILURE;
117 #include "behaviortree_cpp/bt_factory.h"
118 BT_REGISTER_NODES(factory)
A BT::DecoratorNode that ticks its child every time the robot travels a specified distance.
DistanceController(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::DistanceController.