Nav2 Navigation Stack - rolling  main
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_ros_common/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 {
32  auto node = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
33 
34  robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
35  node, "robot_base_frame", this);
36 }
37 
39 {
40  cleanup();
41 }
42 
44 {
45  node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
46 
47  nav2::declare_parameter_if_not_declared(
48  node_, "goal_reached_tol",
49  rclcpp::ParameterValue(0.25));
50  node_->get_parameter_or<double>("goal_reached_tol", goal_reached_tol_, 0.25);
51  tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
52 
53  node_->get_parameter("transform_tolerance", transform_tolerance_);
54 }
55 
57 {
58  if (!BT::isStatusActive(status())) {
59  initialize();
60  }
61 
62  if (isGoalReached()) {
63  return BT::NodeStatus::SUCCESS;
64  }
65  return BT::NodeStatus::FAILURE;
66 }
67 
69 {
70  geometry_msgs::msg::PoseStamped goal;
71  getInput("goal", goal);
72 
73  geometry_msgs::msg::PoseStamped current_pose;
74  if (!nav2_util::getCurrentPose(
75  current_pose, *tf_, goal.header.frame_id, robot_base_frame_, transform_tolerance_))
76  {
77  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
78  return false;
79  }
80 
81  double dx = goal.pose.position.x - current_pose.pose.position.x;
82  double dy = goal.pose.position.y - current_pose.pose.position.y;
83 
84  return (dx * dx + dy * dy) <= (goal_reached_tol_ * goal_reached_tol_);
85 }
86 
87 } // namespace nav2_behavior_tree
88 
89 #include "behaviortree_cpp/bt_factory.h"
90 BT_REGISTER_NODES(factory)
91 {
92  factory.registerNodeType<nav2_behavior_tree::GoalReachedCondition>("GoalReached");
93 }
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.