AutoAPMS
Resilient Robot Mission Management
|
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 | port = "(input:port)" |
Default port name of the corresponding ROS 2 communication interface. | |
std::chrono::duration< double > | wait_timeout = std::chrono::duration<double>(3) |
Period [s] (measured from tree construction) after the server is considered unreachable. | |
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 = "INFO" |
Minimum severity level enabled for logging using the ROS 2 Logger API. | |
Parameters for loading and registering a behavior tree node class from a shared library using e.g. NodeRegistrationLoader.
Definition at line 49 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 29 of file node_registration_options.cpp.
std::string class_name |
Fully qualified name of the behavior tree node plugin class.
Definition at line 66 of file node_registration_options.hpp.
std::string port = "(input:port)" |
Default port name of the corresponding ROS 2 communication interface.
This has different meaning based on the context:
By default, we look for the communication port name using the node's input port named port
.
Definition at line 82 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.
Definition at line 84 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 86 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 89 of file node_registration_options.hpp.
std::string logger_level = "INFO" |
Minimum severity level enabled for logging using the ROS 2 Logger API.
Definition at line 91 of file node_registration_options.hpp.