Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
get_current_pose_action.hpp
1 // Copyright (c) 2025 Open Navigation LLC
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GET_CURRENT_POSE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GET_CURRENT_POSE_ACTION_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "nav_msgs/msg/path.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "nav2_util/geometry_utils.hpp"
25 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_ros_common/lifecycle_node.hpp"
28 
29 #include "behaviortree_cpp/action_node.h"
30 
31 namespace nav2_behavior_tree
32 {
33 
37 class GetCurrentPoseAction : public BT::ActionNodeBase
38 {
39 public:
46  const std::string & xml_tag_name,
47  const BT::NodeConfiguration & conf);
48 
53  static BT::PortsList providedPorts()
54  {
55  return {
56  BT::InputPort<std::string>("global_frame", "Global reference frame"),
57  BT::InputPort<std::string>("robot_base_frame", "robot base frame"),
58  BT::OutputPort<geometry_msgs::msg::PoseStamped>("current_pose", "Current pose output"),
59  };
60  }
61 
62 private:
66  void halt() override {}
67 
72  BT::NodeStatus tick() override;
73 
74  std::string global_frame_, robot_base_frame_;
75  std::shared_ptr<tf2_ros::Buffer> tf_;
76  double transform_tolerance_;
77 };
78 
79 } // namespace nav2_behavior_tree
80 
81 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GET_CURRENT_POSE_ACTION_HPP_
A BT::ActionNodeBase to shorten path by some distance.
static BT::PortsList providedPorts()
Creates list of BT ports.
GetCurrentPoseAction(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::GetCurrentPoseAction constructor.