Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
get_current_pose_action.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Francisco Martin Rico
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 #include <limits>
19 
20 #include "nav_msgs/msg/path.hpp"
21 #include "geometry_msgs/msg/pose_stamped.hpp"
22 #include "nav2_util/geometry_utils.hpp"
23 #include "behaviortree_cpp/decorator_node.h"
24 
25 #include "nav2_behavior_tree/plugins/action/get_current_pose_action.hpp"
26 
27 namespace nav2_behavior_tree
28 {
29 
31  const std::string & name,
32  const BT::NodeConfiguration & conf)
33 : BT::ActionNodeBase(name, conf)
34 {
35  auto node = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
36  tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
37  node->get_parameter("transform_tolerance", transform_tolerance_);
38  global_frame_ = BT::deconflictPortAndParamFrame<std::string>(
39  node, "global_frame", this);
40  robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
41  node, "robot_base_frame", this);
42 }
43 
44 inline BT::NodeStatus GetCurrentPoseAction::tick()
45 {
46  setStatus(BT::NodeStatus::RUNNING);
47  geometry_msgs::msg::PoseStamped current_pose;
48 
49  if (!nav2_util::getCurrentPose(
50  current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_))
51  {
52  RCLCPP_WARN(
53  config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node")->get_logger(),
54  "Current robot pose is not available.");
55  return BT::NodeStatus::FAILURE;
56  }
57 
58  setOutput("current_pose", current_pose);
59  return BT::NodeStatus::SUCCESS;
60 }
61 
62 } // namespace nav2_behavior_tree
63 
64 #include "behaviortree_cpp/bt_factory.h"
65 BT_REGISTER_NODES(factory)
66 {
67  factory.registerNodeType<nav2_behavior_tree::GetCurrentPoseAction>("GetCurrentPose");
68 }
A BT::ActionNodeBase to shorten path by some distance.
GetCurrentPoseAction(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::GetCurrentPoseAction constructor.