AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
node_registration_options.cpp
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#include "auto_apms_behavior_tree_core/node/node_registration_options.hpp"
16
17#include "auto_apms_behavior_tree_core/exceptions.hpp"
18#include "auto_apms_behavior_tree_core/node/node_manifest.hpp"
19
21{
22
23bool NodeRegistrationOptions::valid() const { return !class_name.empty(); }
24
25} // namespace auto_apms_behavior_tree::core
26
28namespace YAML
29{
30
31Node convert<auto_apms_behavior_tree::core::NodeRegistrationOptions>::encode(const Options & rhs)
32{
33 Node node(NodeType::Map);
34 // Note: We intentionally do not encode the 'parent' field, since we directly evaluate it during decoding
35 node[Options::PARAM_NAME_CLASS] = rhs.class_name;
36 node[Options::PARAM_NAME_DESCRIPTION] = rhs.description;
37 node[Options::PARAM_NAME_ROS2TOPIC] = rhs.topic;
38 node[Options::PARAM_NAME_PORT_ALIAS] = rhs.port_alias;
39 node[Options::PARAM_NAME_PORT_DEFAULT] = rhs.port_default;
40 node[Options::PARAM_NAME_HIDDEN_PORTS] = rhs.hidden_ports;
41 node[Options::PARAM_NAME_WAIT_TIMEOUT] = rhs.wait_timeout.count();
42 node[Options::PARAM_NAME_REQUEST_TIMEOUT] = rhs.request_timeout.count();
43 node[Options::PARAM_NAME_ALLOW_UNREACHABLE] = rhs.allow_unreachable;
44 node[Options::PARAM_NAME_LOGGER_LEVEL] = rhs.logger_level;
45 node[Options::PARAM_NAME_EXTRA] = rhs.extra;
46 return node;
47}
48
49bool convert<auto_apms_behavior_tree::core::NodeRegistrationOptions>::decode(
51{
52 using namespace auto_apms_behavior_tree;
53 using namespace auto_apms_behavior_tree::core;
54 using Options = NodeRegistrationOptions;
55
56 if (!node.IsMap())
57 throw auto_apms_util::exceptions::YAMLFormatError(
58 "YAML::Node for auto_apms_behavior_tree::core::NodeRegistrationOptions must be map but is type " +
59 std::to_string(node.Type()) + " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
60
61 // Resolve parent field first (if present) — sets rhs to the inherited parent options as a base.
62 // This avoids the need to track overrides separately: we simply apply the remaining fields on top afterward.
63 if (const Node parent_val = node[Options::PARAM_NAME_PARENT]) {
64 if (!parent_val.IsScalar()) {
65 throw auto_apms_util::exceptions::YAMLFormatError(
66 "Value for key '" + std::string(Options::PARAM_NAME_PARENT) + "' must be scalar but is type " +
67 std::to_string(parent_val.Type()) + " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
68 }
69 const std::string parent_str = parent_val.as<std::string>();
70
71 const std::string id_sep = _AUTO_APMS_BEHAVIOR_TREE_CORE__RESOURCE_IDENTITY_ALIAS_SEP;
72 const std::string node_sep = _AUTO_APMS_BEHAVIOR_TREE_CORE__NODE_NAMESPACE_DEFAULT_SEP;
73
74 // Find the first '.' that follows the '::' separator to split manifest identity from node name
75 const std::size_t id_sep_pos = parent_str.find(id_sep);
76 const std::size_t dot_pos =
77 parent_str.find(node_sep, id_sep_pos != std::string::npos ? id_sep_pos + id_sep.size() : 0);
78
79 if (dot_pos == std::string::npos) {
80 throw exceptions::NodeManifestError(
81 "Invalid parent '" + parent_str + "'. Expected format: '<package_name>" + id_sep + "<manifest_alias>" +
82 node_sep + "<node_name>'.");
83 }
84
85 const std::string manifest_identity_str = parent_str.substr(0, dot_pos);
86 const std::string parent_node_name = parent_str.substr(dot_pos + node_sep.size());
87
88 if (parent_node_name.empty()) {
89 throw exceptions::NodeManifestError("Invalid parent '" + parent_str + "'. Parent node name must not be empty.");
90 }
91
92 try {
93 const NodeManifest parent_manifest =
94 NodeManifest::fromResource(NodeManifestResourceIdentity(manifest_identity_str));
95 if (!parent_manifest.contains(parent_node_name)) {
96 throw exceptions::NodeManifestError(
97 "Parent node '" + parent_node_name + "' does not exist in manifest '" + manifest_identity_str + "'.");
98 }
99 rhs = parent_manifest[parent_node_name];
100 } catch (const exceptions::NodeManifestError &) {
101 throw;
102 } catch (const std::exception & e) {
103 throw exceptions::NodeManifestError(
104 "Failed to load parent manifest '" + manifest_identity_str + "': " + e.what());
105 }
106 }
107
108 // Apply all non-parent fields from the YAML node onto rhs.
109 // For the parent case these act as overrides; for the no-parent case they are the full definition.
110 for (YAML::const_iterator it = node.begin(); it != node.end(); ++it) {
111 const std::string key = it->first.as<std::string>();
112 const Node val = it->second;
113
114 if (key == Options::PARAM_NAME_PARENT) continue; // already handled above
115
116 if (key == Options::PARAM_NAME_EXTRA) {
117 rhs.extra = val;
118 continue;
119 }
120
121 if (key == Options::PARAM_NAME_PORT_ALIAS) {
122 if (!val.IsMap()) {
123 throw auto_apms_util::exceptions::YAMLFormatError(
124 "Value for key '" + key + "' must be a map but is type " + std::to_string(val.Type()) +
125 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
126 }
127 for (const auto & [k, v] : val.as<std::map<std::string, std::string>>()) rhs.port_alias[k] = v;
128 continue;
129 }
130
131 if (key == Options::PARAM_NAME_PORT_DEFAULT) {
132 if (!val.IsMap()) {
133 throw auto_apms_util::exceptions::YAMLFormatError(
134 "Value for key '" + key + "' must be a map but is type " + std::to_string(val.Type()) +
135 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
136 }
137 for (const auto & [k, v] : val.as<std::map<std::string, std::string>>()) rhs.port_default[k] = v;
138 continue;
139 }
140
141 if (key == Options::PARAM_NAME_HIDDEN_PORTS) {
142 if (!val.IsSequence()) {
143 throw auto_apms_util::exceptions::YAMLFormatError(
144 "Value for key '" + key + "' must be a sequence but is type " + std::to_string(val.Type()) +
145 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
146 }
147 for (const auto & entry : val.as<std::vector<std::string>>()) {
148 if (std::find(rhs.hidden_ports.begin(), rhs.hidden_ports.end(), entry) == rhs.hidden_ports.end())
149 rhs.hidden_ports.push_back(entry);
150 }
151 continue;
152 }
153
154 if (key == Options::PARAM_NAME_CLASS) {
155 if (!val.IsScalar()) {
156 throw auto_apms_util::exceptions::YAMLFormatError(
157 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
158 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
159 }
160 rhs.class_name = val.as<std::string>();
161 continue;
162 }
163 if (key == Options::PARAM_NAME_DESCRIPTION) {
164 if (!val.IsScalar()) {
165 throw auto_apms_util::exceptions::YAMLFormatError(
166 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
167 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
168 }
169 rhs.description = val.as<std::string>();
170 continue;
171 }
172 if (key == Options::PARAM_NAME_ROS2TOPIC) {
173 if (!val.IsScalar()) {
174 throw auto_apms_util::exceptions::YAMLFormatError(
175 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
176 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
177 }
178 rhs.topic = val.as<std::string>();
179 continue;
180 }
181 if (key == Options::PARAM_NAME_WAIT_TIMEOUT) {
182 if (!val.IsScalar()) {
183 throw auto_apms_util::exceptions::YAMLFormatError(
184 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
185 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
186 }
187 rhs.wait_timeout = std::chrono::duration<double>(val.as<double>());
188 continue;
189 }
190 if (key == Options::PARAM_NAME_REQUEST_TIMEOUT) {
191 if (!val.IsScalar()) {
192 throw auto_apms_util::exceptions::YAMLFormatError(
193 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
194 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
195 }
196 rhs.request_timeout = std::chrono::duration<double>(val.as<double>());
197 continue;
198 }
199 if (key == Options::PARAM_NAME_ALLOW_UNREACHABLE) {
200 if (!val.IsScalar()) {
201 throw auto_apms_util::exceptions::YAMLFormatError(
202 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
203 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
204 }
205 rhs.allow_unreachable = val.as<bool>();
206 continue;
207 }
208 if (key == Options::PARAM_NAME_LOGGER_LEVEL) {
209 if (!val.IsScalar()) {
210 throw auto_apms_util::exceptions::YAMLFormatError(
211 "Value for key '" + key + "' must be scalar but is type " + std::to_string(val.Type()) +
212 " (0: Undefined - 1: Null - 2: Scalar - 3: Sequence - 4: Map).");
213 }
214 rhs.logger_level = val.as<std::string>();
215 continue;
216 }
217
218 // Unknown parameter
219 throw auto_apms_util::exceptions::YAMLFormatError("Unknown parameter name '" + key + "'.");
220 }
221 return true;
222}
223
224} // namespace YAML
bool contains(const std::string &node_name) const
Determine if a behavior tree node has been added to the manifest.
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).
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...