![]() |
AutoAPMS
Streamlining behaviors in ROS 2
|
Parameters for loading and registering a behavior tree node class from a shared library using e.g. NodeRegistrationLoader. More...
#include <auto_apms_behavior_tree_core/node/node_registration_options.hpp>
Public Member Functions | |
| NodeRegistrationOptions ()=default | |
| Create the default node registration options. | |
| bool | valid () const |
| Verify that the options are valid (e.g. all required values are set). | |
Public Attributes | |
| std::string | class_name |
| Fully qualified name of the behavior tree node plugin class. | |
| std::string | description = "No description provided." |
| Short description of the behavior tree node's purpose and use-case. | |
| std::string | topic = "(input: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::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::chrono::duration< double > | wait_timeout = std::chrono::duration<double>(3) |
| std::chrono::duration< double > | request_timeout = std::chrono::duration<double>(2) |
| Period [s] (measured from sending a goal request) after the node aborts waiting for a server response. | |
| bool | allow_unreachable = false |
| std::string | logger_level = "" |
| Minimum ROS 2 logging severity level for this particular node. Empty means to inherit the parent logging severity. | |
| YAML::Node | extra |
Parameters for loading and registering a behavior tree node class from a shared library using e.g. NodeRegistrationLoader.
Definition at line 31 of file node_registration_options.hpp.
|
default |
Create the default node registration options.
| bool valid | ( | ) | const |
Verify that the options are valid (e.g. all required values are set).
true if valid, false otherwise. Definition at line 34 of file node_registration_options.cpp.
| std::string class_name |
Fully qualified name of the behavior tree node plugin class.
Definition at line 53 of file node_registration_options.hpp.
| std::string description = "No description provided." |
Short description of the behavior tree node's purpose and use-case.
Definition at line 55 of file node_registration_options.hpp.
| std::string topic = "(input:topic)" |
Name of the ROS 2 communication interface to connect with.
This has different meaning based on the context:
It is possible to use a port's value to define this parameter at runtime by using the special pattern (input:<port_name>) and replacing <port_name> with the desired input port name.
Example: Given the user implements an input port BT::InputPort<std::string>("my_port"), one may create a client for the action "foo/bar" by defining NodeRegistrationOptions::port as (input:my_port)/bar and providing the string "foo" to the port with name my_port.
By default, we look for the communication port name using the node's input port named port.
Definition at line 78 of file node_registration_options.hpp.
| std::map<std::string, std::string> port_alias = {} |
Provides the possibility to rename ports implemented by class_name.
This is useful when a node implementation is used in a different context and the meaning of some of the ports has changed. In this case, it's possible to define a more descriptive port name. The description can also be updated by appending it within round brackets.
Example: Given a node implementation with an input port BT::InputPort<std::string>("my_port"), one may alias this port with BT::InputPort<std::string>("new_port") by adding the following entry to the port_alias map:
Definition at line 98 of file node_registration_options.hpp.
| std::map<std::string, std::string> port_default = {} |
Provides the possibility to define custom default values for the ports implemented by class_name.
This will override the "hard-coded" value and allows for configuring a behavior tree node without touching its source file.
Definition at line 109 of file node_registration_options.hpp.
| std::vector<std::string> hidden_ports = {} |
List of port names to hide in the node model for visualization tools like Groot2.
Definition at line 111 of file node_registration_options.hpp.
| std::chrono::duration<double> wait_timeout = std::chrono::duration<double>(3) |
Period [s] (measured from tree construction) after the server is considered unreachable. For publishers, this parameter defines how long to wait for at least one subscriber to connect.
Definition at line 114 of file node_registration_options.hpp.
| std::chrono::duration<double> request_timeout = std::chrono::duration<double>(2) |
Period [s] (measured from sending a goal request) after the node aborts waiting for a server response.
Definition at line 116 of file node_registration_options.hpp.
| bool allow_unreachable = false |
Flag whether to tolerate if the action/service is unreachable when trying to create the client. If set to true, a warning is logged. Otherwise, an exception is raised.
Definition at line 119 of file node_registration_options.hpp.
| std::string logger_level = "" |
Minimum ROS 2 logging severity level for this particular node. Empty means to inherit the parent logging severity.
Definition at line 121 of file node_registration_options.hpp.
| YAML::Node extra |
Flexible YAML node which allows providing additional and customized registration options to the behavior tree node implementation.
Definition at line 124 of file node_registration_options.hpp.