ros2_control - rolling
Public Member Functions | List of all members
realtime_tools::AsyncFunctionHandler< T > Class Template Reference

Class to handle asynchronous function calls. AsyncFunctionHandler is a class that allows the user to have a asynchronous call to the parsed method and be able to set some thread specific parameters. More...

#include <async_function_handler.hpp>

Public Member Functions

void init (std::function< T(const rclcpp::Time &, const rclcpp::Duration &)> callback, int thread_priority=50)
 Initialize the AsyncFunctionHandler with the callback and thread_priority. More...
 
void init (std::function< T(const rclcpp::Time &, const rclcpp::Duration &)> callback, std::function< bool()> trigger_predicate, int thread_priority=50)
 Initialize the AsyncFunctionHandler with the callback, trigger_predicate and thread_priority. More...
 
std::pair< bool, T > trigger_async_callback (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the async callback method cycle. More...
 
void wait_for_trigger_cycle_to_finish ()
 Waits until the current async callback method trigger cycle is finished. More...
 
bool is_initialized () const
 Check if the AsyncFunctionHandler is initialized. More...
 
void join_async_callback_thread ()
 Join the async callback thread. More...
 
bool is_running () const
 Check if the async worker thread is running. More...
 
bool is_stopped () const
 Check if the async callback is triggered to stop the cycle. More...
 
std::thread & get_thread ()
 Get the async worker thread. More...
 
bool is_trigger_cycle_in_progress () const
 Check if the async callback method is in progress. More...
 
void stop_thread ()
 Stops the callback thread. More...
 
double get_last_execution_time () const
 Get the last execution time of the async callback method. More...
 
void start_thread ()
 Initializes and starts the callback thread. More...
 

Detailed Description

template<typename T>
class realtime_tools::AsyncFunctionHandler< T >

Class to handle asynchronous function calls. AsyncFunctionHandler is a class that allows the user to have a asynchronous call to the parsed method and be able to set some thread specific parameters.

Member Function Documentation

◆ get_last_execution_time()

template<typename T >
double realtime_tools::AsyncFunctionHandler< T >::get_last_execution_time ( ) const
inline

Get the last execution time of the async callback method.

Returns
The last execution time of the async callback method in seconds

◆ get_thread()

template<typename T >
std::thread& realtime_tools::AsyncFunctionHandler< T >::get_thread ( )
inline

Get the async worker thread.

Returns
The async callback thread

◆ init() [1/2]

template<typename T >
void realtime_tools::AsyncFunctionHandler< T >::init ( std::function< T(const rclcpp::Time &, const rclcpp::Duration &)>  callback,
int  thread_priority = 50 
)
inline

Initialize the AsyncFunctionHandler with the callback and thread_priority.

Parameters
callbackFunction that will be called asynchronously If the AsyncFunctionHandler is already initialized and is running, it will throw a runtime error. If the parsed functions are not valid, it will throw a runtime error.

◆ init() [2/2]

template<typename T >
void realtime_tools::AsyncFunctionHandler< T >::init ( std::function< T(const rclcpp::Time &, const rclcpp::Duration &)>  callback,
std::function< bool()>  trigger_predicate,
int  thread_priority = 50 
)
inline

Initialize the AsyncFunctionHandler with the callback, trigger_predicate and thread_priority.

Parameters
callbackFunction that will be called asynchronously.
trigger_predicatePredicate function that will be called to check if the async callback method should be triggered or not.
thread_priorityPriority of the async worker thread.
Note
The parsed trigger_predicate should be free from any concurrency issues. It is expected to be both thread-safe and reentrant.

If the AsyncFunctionHandler is already initialized and is running, it will throw a runtime error. If the parsed functions are not valid, it will throw a runtime error.

◆ is_initialized()

template<typename T >
bool realtime_tools::AsyncFunctionHandler< T >::is_initialized ( ) const
inline

Check if the AsyncFunctionHandler is initialized.

Returns
True if the AsyncFunctionHandler is initialized, false otherwise

◆ is_running()

template<typename T >
bool realtime_tools::AsyncFunctionHandler< T >::is_running ( ) const
inline

Check if the async worker thread is running.

Returns
True if the async worker thread is running, false otherwise

◆ is_stopped()

template<typename T >
bool realtime_tools::AsyncFunctionHandler< T >::is_stopped ( ) const
inline

Check if the async callback is triggered to stop the cycle.

Returns
True if the async callback is requested to be stopped, false otherwise

◆ is_trigger_cycle_in_progress()

template<typename T >
bool realtime_tools::AsyncFunctionHandler< T >::is_trigger_cycle_in_progress ( ) const
inline

Check if the async callback method is in progress.

Returns
True if the async callback method is in progress, false otherwise

◆ join_async_callback_thread()

template<typename T >
void realtime_tools::AsyncFunctionHandler< T >::join_async_callback_thread ( )
inline

Join the async callback thread.

If the async method is running, it will join the async thread. If the async method is not running, it will return immediately.

◆ start_thread()

template<typename T >
void realtime_tools::AsyncFunctionHandler< T >::start_thread ( )
inline

Initializes and starts the callback thread.

If the worker thread is not running, it will start the async callback thread. If the worker thread is already configured and running, does nothing and returns immediately.

◆ stop_thread()

template<typename T >
void realtime_tools::AsyncFunctionHandler< T >::stop_thread ( )
inline

Stops the callback thread.

If the async method is running, it will notify the async thread to stop and then joins the async thread.

◆ trigger_async_callback()

template<typename T >
std::pair<bool, T> realtime_tools::AsyncFunctionHandler< T >::trigger_async_callback ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
inline

Triggers the async callback method cycle.

Parameters
timeCurrent time
periodCurrent period
Returns
A pair with the first element being a boolean indicating if the async callback method was triggered and the second element being the last return value of the async function. If the AsyncFunctionHandler is not initialized properly, it will throw a runtime error. If the callback method is waiting for the trigger, it will notify the async thread to start the callback. If the async callback method is still running, it will return the last return value from the last trigger cycle.
Note
In the case of controllers, The controller manager is responsible for triggering and maintaining the controller's update rate, as it should be only acting as a scheduler. Same applies to the resource manager when handling the hardware components.

◆ wait_for_trigger_cycle_to_finish()

template<typename T >
void realtime_tools::AsyncFunctionHandler< T >::wait_for_trigger_cycle_to_finish ( )
inline

Waits until the current async callback method trigger cycle is finished.

If the async method is running, it will wait for the current async method call to finish.


The documentation for this class was generated from the following file: