Template Class AsyncFunctionHandler

Class Documentation

template<typename T>
class AsyncFunctionHandler

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.

Public Functions

AsyncFunctionHandler() = default
inline ~AsyncFunctionHandler()
inline 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.

Parameters:

callback – Function 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.

inline 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.

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.

Note

The parsed trigger_predicate should be free from any concurrency issues. It is expected to be both thread-safe and reentrant.

Parameters:
  • callback – Function that will be called asynchronously.

  • trigger_predicate – Predicate function that will be called to check if the async callback method should be triggered or not.

  • thread_priority – Priority of the async worker thread.

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

Triggers the async callback method 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.

Parameters:
  • time – Current time

  • period – Current 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.

inline void wait_for_trigger_cycle_to_finish()

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.

inline bool is_initialized() const

Check if the AsyncFunctionHandler is initialized.

Returns:

True if the AsyncFunctionHandler is initialized, false otherwise

inline void join_async_callback_thread()

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.

inline bool is_running() const

Check if the async worker thread is running.

Returns:

True if the async worker thread is running, false otherwise

inline bool is_stopped() const

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

Returns:

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

inline std::thread &get_thread()

Get the async worker thread.

Returns:

The async callback thread

inline bool is_trigger_cycle_in_progress() const

Check if the async callback method is in progress.

Returns:

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

inline void stop_thread()

Stops the callback thread.

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

inline double get_last_execution_time() const

Get the last execution time of the async callback method.

Returns:

The last execution time of the async callback method in seconds

inline void start_thread()

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.