Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
initial_pose_received_condition.cpp
1 // Copyright (c) 2019 Intel Corporation
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 "nav2_behavior_tree/plugins/condition/initial_pose_received_condition.hpp"
16 
17 namespace nav2_behavior_tree
18 {
19 InitialPoseReceived::InitialPoseReceived(
20  const std::string & name,
21  const BT::NodeConfiguration & config)
22 : BT::ConditionNode(name, config)
23 {
24 }
25 
26 BT::NodeStatus InitialPoseReceived::tick()
27 {
28  bool initPoseReceived = false;
29  BT::getInputOrBlackboard("initial_pose_received", initPoseReceived);
30  return initPoseReceived ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
31 }
32 
33 } // namespace nav2_behavior_tree
34 
35 #include "behaviortree_cpp/bt_factory.h"
36 BT_REGISTER_NODES(factory)
37 {
38  factory.registerNodeType<nav2_behavior_tree::InitialPoseReceived>("InitialPoseReceived");
39 }
A BT::ConditionNode that returns SUCCESS if initial pose has been received and FAILURE otherwise.