Class LoanedCommandInterface
Defined in File loaned_command_interface.hpp
Nested Relationships
Nested Types
Class Documentation
-
class LoanedCommandInterface
Public Types
-
using Deleter = std::function<void(void)>
Public Functions
-
inline explicit LoanedCommandInterface(CommandInterface &command_interface)
-
inline LoanedCommandInterface(CommandInterface &command_interface, Deleter &&deleter)
-
LoanedCommandInterface(const LoanedCommandInterface &other) = delete
-
LoanedCommandInterface(LoanedCommandInterface &&other) = default
-
inline virtual ~LoanedCommandInterface()
-
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
-
template<typename T>
inline bool set_value(const T &value, unsigned int max_tries = 10) Set the value of the command interface.
Note
The method is thread-safe and non-blocking.
Note
When different threads access the internal 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.
Note
The method will try to set the value max_tries times before returning false. The method will yield the thread between tries. If the value is set successfully, the method returns true immediately.
- Template Parameters:
T – The type of the value to be set.
- Parameters:
value – The value to set.
max_tries – The maximum number of tries to set the value.
- Returns:
true if the value is set successfully, false otherwise.
-
inline double get_value() const
-
template<typename T = double>
inline std::optional<T> get_optional(unsigned int max_tries = 10) const Get the value of the command interface.
Note
The method is thread-safe and non-blocking.
Note
When different threads access the internal 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.
Note
The method will try to get the value max_tries times before returning std::nullopt. The method will yield the thread between tries. If the value is retrieved successfully, the method returns the value immediately.
- Template Parameters:
T – The type of the value to be retrieved.
- Parameters:
max_tries – The maximum number of tries to get the value.
- Returns:
The value of the command interface if it accessed successfully, std::nullopt otherwise.
-
template<typename T>
inline bool get_value(T &value, unsigned int max_tries = 10) const Get the value of the command interface.
Note
The method is thread-safe and non-blocking.
Note
When different threads access the internal 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.
Note
The method will try to get the value max_tries times before returning false. The method will yield the thread between tries. If the value is updated successfully, the method returns true immediately.
- Template Parameters:
T – The type of the value to be retrieved.
- Parameters:
value – The value of the command interface.
max_tries – The maximum number of tries to get the value.
- Returns:
true if the value is accessed successfully, false otherwise.
-
using Deleter = std::function<void(void)>