Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
goal_reached_condition.cpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <string>
16 #include <memory>
17 
18 #include "nav2_util/robot_utils.hpp"
19 #include "geometry_msgs/msg/pose_stamped.hpp"
20 #include "nav2_util/node_utils.hpp"
21 
22 #include "nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp"
23 
24 namespace nav2_behavior_tree
25 {
26 
27 GoalReachedCondition::GoalReachedCondition(
28  const std::string & condition_name,
29  const BT::NodeConfiguration & conf)
30 : BT::ConditionNode(condition_name, conf),
31  initialized_(false),
32  global_frame_("map"),
33  robot_base_frame_("base_link")
34 {
35  getInput("global_frame", global_frame_);
36  getInput("robot_base_frame", robot_base_frame_);
37 }
38 
40 {
41  cleanup();
42 }
43 
45 {
46  if (!initialized_) {
47  initialize();
48  }
49 
50  if (isGoalReached()) {
51  return BT::NodeStatus::SUCCESS;
52  }
53  return BT::NodeStatus::FAILURE;
54 }
55 
57 {
58  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
59 
60  nav2_util::declare_parameter_if_not_declared(
61  node_, "goal_reached_tol",
62  rclcpp::ParameterValue(0.25));
63  node_->get_parameter_or<double>("goal_reached_tol", goal_reached_tol_, 0.25);
64  tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
65 
66  node_->get_parameter("transform_tolerance", transform_tolerance_);
67 
68  initialized_ = true;
69 }
70 
72 {
73  geometry_msgs::msg::PoseStamped current_pose;
74 
75  if (!nav2_util::getCurrentPose(
76  current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_))
77  {
78  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
79  return false;
80  }
81 
82  geometry_msgs::msg::PoseStamped goal;
83  getInput("goal", goal);
84  double dx = goal.pose.position.x - current_pose.pose.position.x;
85  double dy = goal.pose.position.y - current_pose.pose.position.y;
86 
87  return (dx * dx + dy * dy) <= (goal_reached_tol_ * goal_reached_tol_);
88 }
89 
90 } // namespace nav2_behavior_tree
91 
92 #include "behaviortree_cpp_v3/bt_factory.h"
93 BT_REGISTER_NODES(factory)
94 {
95  factory.registerNodeType<nav2_behavior_tree::GoalReachedCondition>("GoalReached");
96 }
A BT::ConditionNode that returns SUCCESS when a specified goal is reached and FAILURE otherwise.
void initialize()
Function to read parameters and initialize class variables.
BT::NodeStatus tick() override
The main override required by a BT action.
~GoalReachedCondition() override
A destructor for nav2_behavior_tree::GoalReachedCondition.
bool isGoalReached()
Checks if the current robot pose lies within a given distance from the goal.