Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
distance_traveled_condition.cpp
1 // Copyright (c) 2019 Intel Corporation
2 // Copyright (c) 2020 Sarthak Mittal
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <string>
17 #include <memory>
18 
19 #include "nav2_util/robot_utils.hpp"
20 #include "nav2_util/geometry_utils.hpp"
21 
22 #include "nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp"
23 
24 namespace nav2_behavior_tree
25 {
26 
27 DistanceTraveledCondition::DistanceTraveledCondition(
28  const std::string & condition_name,
29  const BT::NodeConfiguration & conf)
30 : BT::ConditionNode(condition_name, conf),
31  distance_(1.0),
32  transform_tolerance_(0.1)
33 {
34 }
35 
37 {
38  getInput("distance", distance_);
39 
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_);
43 
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);
48 }
49 
51 {
52  if (!BT::isStatusActive(status())) {
53  initialize();
54  }
55 
56  if (!BT::isStatusActive(status())) {
57  if (!nav2_util::getCurrentPose(
58  start_pose_, *tf_, global_frame_, robot_base_frame_,
59  transform_tolerance_))
60  {
61  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
62  }
63  return BT::NodeStatus::FAILURE;
64  }
65 
66  // Determine distance travelled since we've started this iteration
67  geometry_msgs::msg::PoseStamped current_pose;
68  if (!nav2_util::getCurrentPose(
69  current_pose, *tf_, global_frame_, robot_base_frame_,
70  transform_tolerance_))
71  {
72  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
73  return BT::NodeStatus::FAILURE;
74  }
75 
76  // Get euclidean distance
77  auto travelled = nav2_util::geometry_utils::euclidean_distance(
78  start_pose_.pose, current_pose.pose);
79 
80  if (travelled < distance_) {
81  return BT::NodeStatus::FAILURE;
82  }
83 
84  // Update start pose
85  start_pose_ = current_pose;
86 
87  return BT::NodeStatus::SUCCESS;
88 }
89 
90 } // namespace nav2_behavior_tree
91 
92 #include "behaviortree_cpp/bt_factory.h"
93 BT_REGISTER_NODES(factory)
94 {
95  factory.registerNodeType<nav2_behavior_tree::DistanceTraveledCondition>("DistanceTraveled");
96 }
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.