Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
distance_traveled_condition.hpp
1 // Copyright (c) 2020 Sarthak Mittal
2 // Copyright (c) 2019 Intel Corporation
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__DISTANCE_TRAVELED_CONDITION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__DISTANCE_TRAVELED_CONDITION_HPP_
18 
19 #include <string>
20 #include <memory>
21 
22 #include "behaviortree_cpp_v3/condition_node.h"
23 
24 #include "rclcpp/rclcpp.hpp"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "tf2_ros/buffer.h"
27 
28 namespace nav2_behavior_tree
29 {
30 
35 class DistanceTraveledCondition : public BT::ConditionNode
36 {
37 public:
44  const std::string & condition_name,
45  const BT::NodeConfiguration & conf);
46 
47  DistanceTraveledCondition() = delete;
48 
53  BT::NodeStatus tick() override;
54 
59  static BT::PortsList providedPorts()
60  {
61  return {
62  BT::InputPort<double>("distance", 1.0, "Distance"),
63  BT::InputPort<std::string>("global_frame", std::string("map"), "Global frame"),
64  BT::InputPort<std::string>("robot_base_frame", std::string("base_link"), "Robot base frame")
65  };
66  }
67 
68 private:
69  rclcpp::Node::SharedPtr node_;
70  std::shared_ptr<tf2_ros::Buffer> tf_;
71 
72  geometry_msgs::msg::PoseStamped start_pose_;
73 
74  double distance_;
75  double transform_tolerance_;
76  std::string global_frame_;
77  std::string robot_base_frame_;
78 };
79 
80 } // namespace nav2_behavior_tree
81 
82 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__DISTANCE_TRAVELED_CONDITION_HPP_
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.
static BT::PortsList providedPorts()
Creates list of BT ports.