A handle used to get and set a value on a given interface.
More...
#include <handle.hpp>
|
| Handle (const std::string &prefix_name, const std::string &interface_name, double *value_ptr=nullptr) |
|
| Handle (const InterfaceDescription &interface_description) |
|
| Handle (const std::string &interface_name) |
|
| Handle (const char *interface_name) |
|
| Handle (const Handle &other) noexcept |
|
Handle & | operator= (const Handle &other) |
|
| Handle (Handle &&other) noexcept |
|
Handle & | operator= (Handle &&other) |
|
| operator bool () const |
| Returns true if handle references a value.
|
|
const std::string & | get_name () const |
|
const std::string & | get_interface_name () const |
|
const std::string & | get_full_name () const |
|
const std::string & | get_prefix_name () const |
|
double | get_value () const |
|
template<typename T = double> |
std::optional< T > | get_optional () const |
| Get the value of the handle.
|
|
template<typename T > |
bool | get_value (T &value) const |
| Get the value of the handle.
|
|
template<typename T > |
bool | set_value (const T &value) |
| Set the value of the handle.
|
|
|
std::string | prefix_name_ |
|
std::string | interface_name_ |
|
std::string | handle_name_ |
|
HANDLE_DATATYPE | value_ = std::monostate{} |
|
double * | value_ptr_ |
|
std::shared_mutex | handle_mutex_ |
|
A handle used to get and set a value on a given interface.
◆ get_optional()
template<typename T = double>
std::optional< T > hardware_interface::Handle::get_optional |
( |
| ) |
const |
|
inline |
Get the value of the handle.
- Template Parameters
-
T | The type of the value to be retrieved. |
- Returns
- The value of the handle if it accessed successfully, std::nullopt otherwise.
- Note
- The method is thread-safe and non-blocking.
-
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.
◆ get_value()
template<typename T >
bool hardware_interface::Handle::get_value |
( |
T & |
value | ) |
const |
|
inline |
Get the value of the handle.
- 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.
- Note
- The method is thread-safe and non-blocking.
-
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.
◆ set_value()
template<typename T >
bool hardware_interface::Handle::set_value |
( |
const T & |
value | ) |
|
|
inline |
Set the value of the handle.
- 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.
- Note
- The method is thread-safe and non-blocking.
-
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.
The documentation for this class was generated from the following file:
- ros2_control/hardware_interface/include/hardware_interface/handle.hpp