Nav2 Navigation Stack - humble  humble
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  global_frame_("map"),
34  robot_base_frame_("base_link")
35 {
36  getInput("distance", distance_);
37  getInput("global_frame", global_frame_);
38  getInput("robot_base_frame", robot_base_frame_);
39  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
40  tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
41  node_->get_parameter("transform_tolerance", transform_tolerance_);
42 }
43 
45 {
46  if (status() == BT::NodeStatus::IDLE) {
47  if (!nav2_util::getCurrentPose(
48  start_pose_, *tf_, global_frame_, robot_base_frame_,
49  transform_tolerance_))
50  {
51  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
52  }
53  return BT::NodeStatus::FAILURE;
54  }
55 
56  // Determine distance travelled since we've started this iteration
57  geometry_msgs::msg::PoseStamped current_pose;
58  if (!nav2_util::getCurrentPose(
59  current_pose, *tf_, global_frame_, robot_base_frame_,
60  transform_tolerance_))
61  {
62  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
63  return BT::NodeStatus::FAILURE;
64  }
65 
66  // Get euclidean distance
67  auto travelled = nav2_util::geometry_utils::euclidean_distance(
68  start_pose_.pose, current_pose.pose);
69 
70  if (travelled < distance_) {
71  return BT::NodeStatus::FAILURE;
72  }
73 
74  // Update start pose
75  start_pose_ = current_pose;
76 
77  return BT::NodeStatus::SUCCESS;
78 }
79 
80 } // namespace nav2_behavior_tree
81 
82 #include "behaviortree_cpp_v3/bt_factory.h"
83 BT_REGISTER_NODES(factory)
84 {
85  factory.registerNodeType<nav2_behavior_tree::DistanceTraveledCondition>("DistanceTraveled");
86 }
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.