15#include "auto_apms_behavior_tree_core/node/ros_node_context.hpp"
20#include "auto_apms_behavior_tree_core/exceptions.hpp"
21#include "auto_apms_util/logging.hpp"
26 rclcpp::Node::SharedPtr ros_node, rclcpp::CallbackGroup::SharedPtr tree_node_waitables_callback_group,
27 rclcpp::executors::SingleThreadedExecutor::SharedPtr tree_node_waitables_executor,
29: ros_node_name_(ros_node ? ros_node->get_name() :
""),
30 fully_qualified_ros_node_name_(ros_node ? ros_node->get_fully_qualified_name() :
""),
31 base_logger_(ros_node ? ros_node->get_logger() : rclcpp::get_logger(
"")),
33 cb_group_(tree_node_waitables_callback_group),
34 executor_(tree_node_waitables_executor),
35 registration_options_(options)
47 const rclcpp::Logger child_logger = base_logger_.get_child(name);
48 if (!registration_options_.logger_level.empty()) {
51 }
catch (
const auto_apms_util::exceptions::SetLoggingSeverityError & e) {
54 "Failed to set the logging severity for the child logger using the node's registration options: %s", e.what());
62 if (
const rclcpp::Node::SharedPtr node = nh_.lock()) {
65 return rclcpp::Clock(RCL_ROS_TIME).now();
72 const std::string instance_name = node->name();
73 const std::string registration_name = node->registrationName();
74 if (!registration_name.empty() && instance_name != registration_name) {
75 if (with_class_name) {
76 return instance_name +
" (" + registration_name +
" : " + registration_options_.class_name +
")";
78 return instance_name +
" (" + registration_name +
")";
80 return with_class_name ? (instance_name +
" (" + registration_options_.class_name +
")") : instance_name;
85BT::Expected<std::string> RosNodeContext::getTopicName(
const BT::TreeNode * node)
const
87 std::string res = registration_options_.
topic;
89 return nonstd::make_unexpected(
91 " - Cannot get the name of the node's associated ROS 2 topic: Registration option '" +
92 NodeRegistrationOptions::PARAM_NAME_ROS2TOPIC +
"' is empty.");
94 BT::PortsRemapping input_ports = node->config().input_ports;
99 const std::regex pattern(R
"(\(input:([^)\s]+)\))");
100 const std::sregex_iterator replace_begin(res.begin(), res.end(), pattern);
101 const std::sregex_iterator replace_end = std::sregex_iterator();
105 for (std::sregex_iterator it = replace_begin; it != replace_end; ++it) {
106 const std::smatch match = *it;
107 const std::string input_port_key = match[1].str();
110 if (input_ports.find(input_port_key) != input_ports.end()) {
114 if (input_ports.at(input_port_key).empty()) {
115 return nonstd::make_unexpected(
117 " - Cannot get the name of the node's associated ROS 2 topic: Input port '" + input_port_key +
118 "' required by substring '" + match.str() +
"' must not be empty.");
124 const BT::Expected<std::string> expected = node->getInput<std::string>(input_port_key);
127 res.replace(match.position(), match.length(), expected.value());
133 return nonstd::make_unexpected(
135 " - Cannot get the name of the node's associated ROS 2 topic: Input port '" + input_port_key +
136 "' required by substring '" + match.str() +
"' doesn't exist.");
149 static const std::regex alias_regex(R
"(^\s*([^\s(]+)\s*(?:\(([^)]*)\))?\s*$)");
151 if (std::regex_match(str, match, alias_regex)) {
152 return {match[1].str(), match[2].str()};
157void RosNodeContext::modifyProvidedPortsListForRegistration(BT::PortsList & ports_list)
const
161 std::map<std::string, std::string> original_alias_name_map;
162 for (
const auto & [original_port_name, aliased_port_name] : registration_options_.
port_alias) {
163 if (ports_list.find(original_port_name) == ports_list.end()) {
164 throw exceptions::NodeRegistrationError(
165 "Cannot alias port '" + original_port_name +
"' which is not provided by class '" +
166 registration_options_.
class_name +
"'. The keys under " + NodeRegistrationOptions::PARAM_NAME_PORT_ALIAS +
167 " must refer to a port implemented by the node.");
169 BT::PortInfo port_info = ports_list.at(original_port_name);
170 const auto [aliased_name_cleaned, aliased_description] =
parseAliasPortName(aliased_port_name);
171 original_alias_name_map[original_port_name] = aliased_name_cleaned;
174 if (!aliased_description.empty()) {
175 port_info.setDescription(aliased_description);
179 ports_list.insert({aliased_name_cleaned, port_info});
183 for (
const auto & [port_name, new_default] : registration_options_.port_default) {
184 if (ports_list.find(port_name) == ports_list.end()) {
185 throw exceptions::NodeRegistrationError(
186 "Cannot set default value for port '" + port_name +
"' which is not provided by class '" +
187 registration_options_.class_name +
"'. The keys under " + NodeRegistrationOptions::PARAM_NAME_PORT_DEFAULT +
188 " must refer to a port implemented by the node.");
192 ports_list.at(port_name).setDefaultValue(new_default);
195 if (original_alias_name_map.find(port_name) != original_alias_name_map.end()) {
197 const std::string aliased_port_name = original_alias_name_map.at(port_name);
198 ports_list.at(aliased_port_name).setDefaultValue(new_default);
200 for (
const auto & [original_port_name, aliased_port_name] : original_alias_name_map) {
201 if (aliased_port_name == port_name) {
203 ports_list.at(original_port_name).setDefaultValue(new_default);
211BT::PortsRemapping RosNodeContext::copyAliasedPortValuesToOriginalPorts(
const BT::TreeNode * node)
const
213 const BT::PortsRemapping & input_ports = node->config().input_ports;
214 const BT::PortsRemapping & output_ports = node->config().output_ports;
216 BT::PortsRemapping remapping;
219 auto process_ports = [&](
const BT::PortsRemapping & node_ports) {
220 for (
const auto & [original_key, port_info] : node_ports) {
222 const auto alias_it = registration_options_.port_alias.find(original_key);
223 if (alias_it != registration_options_.port_alias.end()) {
226 auto aliased_port_it = node_ports.find(aliased_port_name);
227 if (aliased_port_it != node_ports.end()) {
229 remapping[original_key] = aliased_port_it->second;
231 throw exceptions::NodeRegistrationError(
232 "Error processing port aliasing: Cannot find aliased port '" + aliased_port_name +
"' for original port '" +
242 process_ports(input_ports);
243 process_ports(output_ports);
std::string getROSNodeName() const
Get the name of the ROS 2 node passed to the constructor.
rclcpp::Logger getChildLogger(const std::string &name)
Get a child logger created using the associated ROS 2 node.
rclcpp::Time getCurrentTime() const
Get the current time using the associated ROS 2 node.
RosNodeContext(rclcpp::Node::SharedPtr ros_node, rclcpp::CallbackGroup::SharedPtr tree_node_waitables_callback_group, rclcpp::executors::SingleThreadedExecutor::SharedPtr tree_node_waitables_executor, const NodeRegistrationOptions &options)
Constructor.
std::string getFullyQualifiedTreeNodeName(const BT::TreeNode *node, bool with_class_name=true) const
Create a string representing the detailed name of a behavior tree node.
std::string getFullyQualifiedRosNodeName() const
Get the fully qualified name of the ROS 2 node passed to the constructor.
YAML::Node getExtraOptions() const
Get the extra YAML options provided during node registration.
rclcpp::Logger getBaseLogger() const
Get the logger of the associated ROS 2 node.
void setLoggingSeverity(const rclcpp::Logger &logger, const std::string &severity)
Set the logging severity of a ROS 2 logger.
Core API for AutoAPMS's behavior tree implementation.
std::pair< std::string, std::string > parseAliasPortName(const std::string &str)
Parse alias port name and optional description from format "alias_name" or "alias_name (description)"...
Parameters for loading and registering a behavior tree node class from a shared library using e....
std::string topic
Name of the ROS 2 communication interface to connect with.
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.