AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
node_registration_options.hpp
1// Copyright 2024 Robin Müller
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#pragma once
16
17#include <chrono>
18#include <map>
19#include <string>
20
21#include "auto_apms_util/exceptions.hpp"
22#include "auto_apms_util/yaml.hpp"
23
25{
26
32{
33 inline static const std::string PARAM_NAME_CLASS = "class_name";
34 inline static const std::string PARAM_NAME_ROS2TOPIC = "topic";
35 inline static const std::string PARAM_NAME_DESCRIPTION = "description";
36 inline static const std::string PARAM_NAME_PORT_ALIAS = "port_alias";
37 inline static const std::string PARAM_NAME_PORT_DEFAULT = "port_default";
38 inline static const std::string PARAM_NAME_WAIT_TIMEOUT = "wait_timeout";
39 inline static const std::string PARAM_NAME_REQUEST_TIMEOUT = "request_timeout";
40 inline static const std::string PARAM_NAME_ALLOW_UNREACHABLE = "allow_unreachable";
41 inline static const std::string PARAM_NAME_LOGGER_LEVEL = "logger_level";
42 inline static const std::string PARAM_NAME_HIDDEN_PORTS = "hidden_ports";
43 inline static const std::string PARAM_NAME_EXTRA = "extra";
44 inline static const std::string PARAM_NAME_PARENT = "parent";
45
50
52
53
54 std::string class_name;
56 std::string description = "No description provided.";
79 std::string topic = "(input:topic)";
99 std::map<std::string, std::string> port_alias = {};
110 std::map<std::string, std::string> port_default = {};
112 std::vector<std::string> hidden_ports = {};
115 std::chrono::duration<double> wait_timeout = std::chrono::duration<double>(5);
117 std::chrono::duration<double> request_timeout = std::chrono::duration<double>(5);
120 bool allow_unreachable = false;
122 std::string logger_level = "";
125 YAML::Node extra;
126
131 bool valid() const;
132};
133
134} // namespace auto_apms_behavior_tree::core
135
136// #####################################################################################################################
137// ################################ DEFINITIONS ##############################################
138// #####################################################################################################################
139
141namespace YAML
142{
143template <>
145{
147 static Node encode(const Options & rhs);
148 static bool decode(const Node & node, Options & rhs);
149};
150
151} // namespace YAML
#define AUTO_APMS_UTIL_DEFINE_YAML_CONVERSION_METHODS(ClassType)
Macro for defining YAML encode/decode methods for a class.
Definition yaml.hpp:32
Core API for AutoAPMS's behavior tree implementation.
Definition behavior.hpp:32
Powerful tooling for incorporating behavior trees for task development.
Definition behavior.hpp:32
Parameters for loading and registering a behavior tree node class from a shared library using e....
std::string description
Short description of the behavior tree node's purpose and use-case.
bool valid() const
Verify that the options are valid (e.g. all required values are set).
NodeRegistrationOptions()=default
Create the default node registration options.
std::string topic
Name of the ROS 2 communication interface to connect with.
std::chrono::duration< double > request_timeout
Period [s] (measured from sending a goal request) after the node aborts waiting for a server response...
std::map< std::string, std::string > port_default
Provides the possibility to define custom default values for the ports implemented by class_name.
std::vector< std::string > hidden_ports
List of port names to hide in the node model for visualization tools like Groot2.
std::map< std::string, std::string > port_alias
Provides the possibility to rename ports implemented by class_name.
std::string class_name
Fully qualified name of the behavior tree node plugin class.
std::string logger_level
Minimum ROS 2 logging severity level for this particular node. Empty means to inherit the parent logg...