The AsyncFunctionHandlerParams struct is used to configure the AsyncFunctionHandler. If the type is SYNCHRONIZED, the async worker thread will be synchronized with the main thread, as the main thread will be triggering the async callback method. If the type is DETACHED, the async worker thread will be detached from the main thread and will have its own execution cycle.
More...
#include <async_function_handler.hpp>
|
bool | validate () const |
| Validate the parameters.
|
|
template<typename NodeT > |
void | initialize (NodeT &node, const std::string &prefix) |
| Initialize the parameters from a node's parameters. The node should have the following parameters:
|
|
|
int | thread_priority = 50 |
|
std::vector< int > | cpu_affinity_cores = {} |
|
AsyncSchedulingPolicy | scheduling_policy = AsyncSchedulingPolicy::SYNCHRONIZED |
|
unsigned int | exec_rate = 0u |
|
rclcpp::Clock::SharedPtr | clock = nullptr |
|
rclcpp::Logger | logger = rclcpp::get_logger("AsyncFunctionHandler") |
|
std::function< bool()> | trigger_predicate = []() { return true; } |
|
bool | wait_until_initial_trigger = true |
|
bool | print_warnings = true |
|
The AsyncFunctionHandlerParams struct is used to configure the AsyncFunctionHandler. If the type is SYNCHRONIZED, the async worker thread will be synchronized with the main thread, as the main thread will be triggering the async callback method. If the type is DETACHED, the async worker thread will be detached from the main thread and will have its own execution cycle.
- Parameters
-
thread_priority | Priority of the async worker thread. Should be between 0 and 99. |
cpu_affinity_cores | CPU cores to which the async worker thread should be pinned. If empty, the thread will not be pinned to any CPU core. |
scheduling_policy | Scheduling policy for the async worker thread. Can be either SYNCHRONIZED or DETACHED. |
exec_rate | Execution rate of the async worker thread in Hz. Only used if the scheduling_policy is DETACHED. Must be a positive integer. |
clock | Clock to be used for the async worker thread. Only used if the scheduling_policy is DETACHED. |
logger | Logger to be used for the async worker thread. If not set, a default logger will be used. |
trigger_predicate | Predicate function to check if the async callback method should be triggered or not. If not set, the async callback method will be triggered every time. |
wait_until_initial_trigger | Whether to wait until the initial trigger predicate is true before starting the async callback method. If true, the async callback method will not be called until the trigger predicate returns true for the first time. Very useful when the type is DETACHED. |
print_warnings | Whether to print warnings when the async callback method is not triggered due to any reason. |
◆ initialize()
template<typename NodeT >
void realtime_tools::AsyncFunctionHandlerParams::initialize |
( |
NodeT & |
node, |
|
|
const std::string & |
prefix |
|
) |
| |
|
inline |
Initialize the parameters from a node's parameters. The node should have the following parameters:
- thread_priority (int): Priority of the async worker thread. Default is 50.
- cpu_affinity (int[]): CPU cores to which the async worker thread should be pinned. Default is empty, which means the thread will not be pinned to any CPU core.
- scheduling_policy (string): Scheduling policy for the async worker thread. Can be either "synchronized" or "detached". Default is "synchronized".
- execution_rate (int): Execution rate of the async worker thread in Hz.
- wait_until_initial_trigger (bool): Whether to wait until the initial trigger predicate is true before starting the async callback method. Default is true.
- print_warnings (bool): Whether to print warnings when the async callback method is not triggered due to any reason. Default is true.
- Parameters
-
node | The node that is used to get the parameters. |
prefix | Parameter prefix to use when accessing node parameters. |
◆ validate()
bool realtime_tools::AsyncFunctionHandlerParams::validate |
( |
| ) |
const |
|
inline |
Validate the parameters.
- Returns
- true if the parameters are valid, false otherwise.
- Exceptions
-
std::runtime_error | if the scheduling policy is UNKNOWN. |
The documentation for this struct was generated from the following file: