Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
globally_updated_goal_condition.cpp
1 // Copyright (c) 2021 Joshua Wallace
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 #include <vector>
16 #include <string>
17 
18 #include "nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp"
19 
20 namespace nav2_behavior_tree
21 {
22 
23 GloballyUpdatedGoalCondition::GloballyUpdatedGoalCondition(
24  const std::string & condition_name,
25  const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf),
27  first_time(true)
28 {
29  node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
30 }
31 
33 {
34  if (first_time) {
35  first_time = false;
36  config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals", goals_);
37  config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal", goal_);
38  return BT::NodeStatus::SUCCESS;
39  }
40 
41  std::vector<geometry_msgs::msg::PoseStamped> current_goals;
42  config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals", current_goals);
43  geometry_msgs::msg::PoseStamped current_goal;
44  config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal", current_goal);
45 
46  if (goal_ != current_goal || goals_ != current_goals) {
47  goal_ = current_goal;
48  goals_ = current_goals;
49  return BT::NodeStatus::SUCCESS;
50  }
51 
52  return BT::NodeStatus::FAILURE;
53 }
54 
55 } // namespace nav2_behavior_tree
56 
57 #include "behaviortree_cpp_v3/bt_factory.h"
58 BT_REGISTER_NODES(factory)
59 {
60  factory.registerNodeType<nav2_behavior_tree::GloballyUpdatedGoalCondition>("GlobalUpdatedGoal");
61 }
A BT::ConditionNode that returns SUCCESS when goal is updated on the blackboard and FAILURE otherwise...
BT::NodeStatus tick() override
The main override required by a BT action.