Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
distance_controller.cpp
1 // Copyright (c) 2018 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 <chrono>
17 #include <string>
18 #include <memory>
19 #include <cmath>
20 
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"
25 
26 #include "behaviortree_cpp/decorator_node.h"
27 
28 #include "nav2_behavior_tree/plugins/decorator/distance_controller.hpp"
29 
30 namespace nav2_behavior_tree
31 {
32 
34  const std::string & name,
35  const BT::NodeConfiguration & conf)
36 : BT::DecoratorNode(name, conf),
37  distance_(1.0),
38  first_time_(false)
39 {
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_);
44 
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);
49 }
50 
51 inline BT::NodeStatus DistanceController::tick()
52 {
53  if (!BT::isStatusActive(status())) {
54  // Reset the starting position since we're starting a new iteration of
55  // the distance controller (moving from IDLE to RUNNING)
56  if (!nav2_util::getCurrentPose(
57  start_pose_, *tf_, global_frame_, robot_base_frame_,
58  transform_tolerance_))
59  {
60  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
61  return BT::NodeStatus::FAILURE;
62  }
63  first_time_ = true;
64  }
65 
66  setStatus(BT::NodeStatus::RUNNING);
67 
68  // Determine distance travelled since we've started this iteration
69  geometry_msgs::msg::PoseStamped current_pose;
70  if (!nav2_util::getCurrentPose(
71  current_pose, *tf_, global_frame_, robot_base_frame_,
72  transform_tolerance_))
73  {
74  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
75  return BT::NodeStatus::FAILURE;
76  }
77 
78  // Get euclidean distance
79  auto travelled = nav2_util::geometry_utils::euclidean_distance(
80  start_pose_.pose, current_pose.pose);
81 
82  // The child gets ticked the first time through and every time the threshold
83  // distance is crossed. In addition, once the child begins to run, it is
84  // ticked each time 'til completion
85  if (first_time_ || (child_node_->status() == BT::NodeStatus::RUNNING) ||
86  travelled >= distance_)
87  {
88  first_time_ = false;
89  const BT::NodeStatus child_state = child_node_->executeTick();
90 
91  switch (child_state) {
92  case BT::NodeStatus::SKIPPED:
93  case BT::NodeStatus::RUNNING:
94  return child_state;
95 
96  case BT::NodeStatus::SUCCESS:
97  if (!nav2_util::getCurrentPose(
98  start_pose_, *tf_, global_frame_, robot_base_frame_,
99  transform_tolerance_))
100  {
101  RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
102  return BT::NodeStatus::FAILURE;
103  }
104  return BT::NodeStatus::SUCCESS;
105 
106  case BT::NodeStatus::FAILURE:
107  default:
108  return BT::NodeStatus::FAILURE;
109  }
110  }
111 
112  return status();
113 }
114 
115 } // namespace nav2_behavior_tree
116 
117 #include "behaviortree_cpp/bt_factory.h"
118 BT_REGISTER_NODES(factory)
119 {
120  factory.registerNodeType<nav2_behavior_tree::DistanceController>("DistanceController");
121 }
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.