15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GET_CURRENT_POSE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__GET_CURRENT_POSE_ACTION_HPP_
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"
28 #include "behaviortree_cpp/action_node.h"
30 namespace nav2_behavior_tree
45 const std::string & xml_tag_name,
46 const BT::NodeConfiguration & conf);
55 BT::InputPort<std::string>(
"global_frame",
"Global reference frame"),
56 BT::InputPort<std::string>(
"robot_base_frame",
"robot base frame"),
57 BT::OutputPort<geometry_msgs::msg::PoseStamped>(
"current_pose",
"Current pose output"),
65 void halt()
override {}
71 BT::NodeStatus tick()
override;
73 std::string global_frame_, robot_base_frame_;
74 std::shared_ptr<tf2_ros::Buffer> tf_;
75 double transform_tolerance_;
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.