Class Handle

Inheritance Relationships

Derived Types

Class Documentation

class Handle

A handle used to get and set a value on a given interface.

Subclassed by hardware_interface::CommandInterface, hardware_interface::StateInterface

Public Functions

inline Handle(const std::string &prefix_name, const std::string &interface_name, double *value_ptr)
inline explicit Handle(const std::string &prefix_name, const std::string &interface_name, const std::string &data_type = "double", const std::string &initial_value = "")
inline explicit Handle(const InterfaceDescription &interface_description)
inline explicit Handle(const std::string &interface_name)
inline explicit Handle(const char *interface_name)
inline Handle(const Handle &other) noexcept
inline Handle &operator=(const Handle &other)
inline Handle(Handle &&other) noexcept
inline Handle &operator=(Handle &&other)
virtual ~Handle() = default
inline operator bool() const

Returns true if handle references a value.

inline const std::string &get_name() const
inline const std::string &get_interface_name() const
inline const std::string &get_prefix_name() const
template<typename T = double>
inline std::optional<T> get_optional() const

Get the value of the handle.

Note

The method is thread-safe and non-blocking.

Note

When different threads access the same handle at same instance, and if they are unable to lock the handle to access the value, the handle returns std::nullopt. If the operation is successful, the value is returned.

Template Parameters:

T – The type of the value to be retrieved.

Returns:

The value of the handle if it accessed successfully, std::nullopt otherwise.

template<typename T = double>
inline std::optional<T> get_optional(std::shared_lock<std::shared_mutex> &lock) const

Get the value of the handle.

Note

The method is thread-safe and non-blocking.

Note

When different threads access the same handle at same instance, and if they are unable to lock the handle to access the value, the handle returns std::nullopt. If the operation is successful, the value is returned.

Template Parameters:

T – The type of the value to be retrieved.

Parameters:

lock – The lock to access the value.

Returns:

The value of the handle if it accessed successfully, std::nullopt otherwise.

template<typename T, typename = std::enable_if_t<!std::is_same_v<std::decay_t<T>, std::shared_lock<std::shared_mutex>>>>
inline bool get_value(T &value, bool wait_for_lock) const

Get the value of the handle.

Note

The method is thread-safe.

Note

This method is real-time safe or non-blocking, only if wait_for_lock is set to false.

Note

Ideal for the data types that are large in size to avoid copy during return.

Template Parameters:

T – The type of the value to be retrieved.

Parameters:
  • value – The variable to store the retrieved value.

  • wait_for_lock – If true, the method will wait for the lock to be available, else it will try to get the lock without blocking.

Returns:

true if the value is retrieved successfully, false otherwise.

template<typename T>
inline bool set_value(const T &value, bool wait_for_lock)

Set the value of the handle.

Note

The method is thread-safe.

Note

This method is real-time safe or non-blocking, only if wait_for_lock is set to false.

Template Parameters:

T – The type of the value to be set.

Parameters:
  • value – The value to be set.

  • wait_for_lock – If true, the method will wait for the lock to be available, else it will try to get the lock without blocking.

Returns:

true if the value is set successfully, false otherwise.

template<typename T>
inline bool set_value(const T &value)

Set the value of the handle.

Note

The method is thread-safe and non-blocking.

Note

When different threads access the same handle at same instance, and if they are unable to lock the handle to set the value, the handle returns false. If the operation is successful, the handle is updated and returns true.

Template Parameters:

T – The type of the value to be set.

Parameters:

value – The value to be set.

Returns:

true if the value is set successfully, false otherwise.

template<typename T>
inline bool set_value(std::unique_lock<std::shared_mutex> &lock, const T &value)

Set the value of the handle.

Note

The method is thread-safe and non-blocking.

Note

When different threads access the same handle at same instance, and if they are unable to lock the handle to set the value, the handle returns false. If the operation is successful, the handle is updated and returns true.

Template Parameters:

T – The type of the value to be set.

Parameters:
  • lock – The lock to set the value.

  • value – The value to be set.

Returns:

true if the value is set successfully, false otherwise.

inline std::shared_mutex &get_mutex() const
inline HandleDataType get_data_type() const
inline bool is_castable_to_double() const

Returns true if the handle data type can be casted to double.

inline bool is_valid() const

Protected Functions

template<typename T>
inline bool get_value(std::shared_lock<std::shared_mutex> &lock, T &value) const

Get the value of the handle.

Note

The method is thread-safe and non-blocking.

Note

Ideal for the data types that are large in size to avoid copy during return.

Template Parameters:

T – The type of the value to be retrieved.

Parameters:
  • lock – The lock to access the value.

  • value – The variable to store the retrieved value.

Returns:

true if the value is retrieved successfully, false otherwise.

Protected Attributes

std::string prefix_name_
std::string interface_name_
std::string handle_name_
HANDLE_DATATYPE value_ = std::monostate{}
HandleDataType data_type_ = HandleDataType::DOUBLE
double *value_ptr_ = nullptr
mutable std::shared_mutex handle_mutex_