Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
initial_pose_received_condition.hpp
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__INITIAL_POSE_RECEIVED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__INITIAL_POSE_RECEIVED_CONDITION_HPP_
17 
18 #include <string>
19 #include "behaviortree_cpp/behavior_tree.h"
20 #include "nav2_behavior_tree/bt_utils.hpp"
21 
22 namespace nav2_behavior_tree
23 {
28 class InitialPoseReceived : public BT::ConditionNode
29 {
30 public:
32  const std::string & name,
33  const BT::NodeConfiguration & config);
34 
35  static BT::PortsList providedPorts()
36  {
37  return {BT::InputPort<bool>("initial_pose_received")};
38  }
39 
40  BT::NodeStatus tick() override;
41 };
42 
43 } // namespace nav2_behavior_tree
44 
45 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__INITIAL_POSE_RECEIVED_CONDITION_HPP_
A BT::ConditionNode that returns SUCCESS if initial pose has been received and FAILURE otherwise.