15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_ERROR_CODES_PRESENT_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_ERROR_CODES_PRESENT_CONDITION_HPP_
23 #include "nav2_ros_common/lifecycle_node.hpp"
24 #include "behaviortree_cpp/condition_node.h"
26 namespace nav2_behavior_tree
33 const std::string & condition_name,
34 const BT::NodeConfiguration & conf)
35 : BT::ConditionNode(condition_name, conf)
37 std::vector<int> error_codes_to_check_vector;
38 getInput(
"error_codes_to_check", error_codes_to_check_vector);
40 error_codes_to_check_ = std::set<uint16_t>(
41 error_codes_to_check_vector.begin(),
42 error_codes_to_check_vector.end());
49 getInput<uint16_t>(
"error_code", error_code_);
51 if (error_codes_to_check_.find(error_code_) != error_codes_to_check_.end()) {
52 return BT::NodeStatus::SUCCESS;
55 return BT::NodeStatus::FAILURE;
58 static BT::PortsList providedPorts()
62 BT::InputPort<uint16_t>(
"error_code",
"The active error codes"),
63 BT::InputPort<std::vector<int>>(
"error_codes_to_check",
"Error codes to check")
69 std::set<uint16_t> error_codes_to_check_;