AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
NodeRegistrationOptions Struct Reference

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.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ NodeRegistrationOptions()

Create the default node registration options.

Member Function Documentation

◆ valid()

bool valid ( ) const

Verify that the options are valid (e.g. all required values are set).

Returns
true if valid, false otherwise.

Definition at line 29 of file node_registration_options.cpp.

Member Data Documentation

◆ class_name

std::string class_name

Fully qualified name of the behavior tree node plugin class.

Definition at line 66 of file node_registration_options.hpp.

◆ port

std::string port = "(input:port)"

Default port name of the corresponding ROS 2 communication interface.

This has different meaning based on the context:

It is possible to customize which port is used to determine the action/service/topic name and also extend the input's value with a prefix or suffix. This is achieved by using the special pattern (input:<port_name>) in 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 90 of file node_registration_options.hpp.

◆ wait_timeout

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 92 of file node_registration_options.hpp.

◆ request_timeout

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 94 of file node_registration_options.hpp.

◆ allow_unreachable

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 97 of file node_registration_options.hpp.

◆ logger_level

std::string logger_level = "INFO"

Minimum severity level enabled for logging using the ROS 2 Logger API.

Definition at line 99 of file node_registration_options.hpp.


The documentation for this struct was generated from the following files: