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 = nullptr)
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_full_name() const
inline const std::string &get_prefix_name() const
inline double get_value() 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>
inline bool get_value(T &value) 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 false. If the operation is successful, the value is updated and returns true.

Template Parameters:

T – The type of the value to be retrieved.

Parameters:

value – The value of the handle.

Returns:

true if the value is accessed 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.

Protected Attributes

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