ros2_control - rolling
Loading...
Searching...
No Matches
Classes | Public Types | Public Member Functions | Protected Attributes | List of all members
hardware_interface::LoanedCommandInterface Class Reference
Collaboration diagram for hardware_interface::LoanedCommandInterface:
Collaboration graph
[legend]

Public Types

using Deleter = std::function< void(void)>
 

Public Member Functions

 LoanedCommandInterface (CommandInterface &command_interface)
 
 LoanedCommandInterface (CommandInterface &command_interface, Deleter &&deleter)
 
 LoanedCommandInterface (CommandInterface::SharedPtr command_interface, Deleter &&deleter)
 
 LoanedCommandInterface (const LoanedCommandInterface &other)=delete
 
 LoanedCommandInterface (LoanedCommandInterface &&other)=default
 
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
 
template<typename T >
bool set_value (const T &value, unsigned int max_tries=10)
 Set the value of the command interface.
 
double get_value () const
 
template<typename T = double>
std::optional< T > get_optional (unsigned int max_tries=10) const
 Get the value of the command interface.
 
template<typename T >
bool get_value (T &value, unsigned int max_tries=10) const
 Get the value of the command interface.
 

Protected Attributes

CommandInterfacecommand_interface_
 
Deleter deleter_
 

Member Function Documentation

◆ get_optional()

template<typename T = double>
std::optional< T > hardware_interface::LoanedCommandInterface::get_optional ( unsigned int  max_tries = 10) const
inline

Get the value of the command interface.

Template Parameters
TThe type of the value to be retrieved.
Returns
The value of the command interface if it accessed successfully, std::nullopt otherwise.
Parameters
max_triesThe maximum number of tries to get the value.
Note
The method is thread-safe and non-blocking.
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.
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.

◆ get_value()

template<typename T >
bool hardware_interface::LoanedCommandInterface::get_value ( T &  value,
unsigned int  max_tries = 10 
) const
inline

Get the value of the command interface.

Template Parameters
TThe type of the value to be retrieved.
Parameters
valueThe value of the command interface.
max_triesThe maximum number of tries to get the value.
Returns
true if the value is accessed successfully, false otherwise.
Note
The method is thread-safe and non-blocking.
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.
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.

◆ set_value()

template<typename T >
bool hardware_interface::LoanedCommandInterface::set_value ( const T &  value,
unsigned int  max_tries = 10 
)
inline

Set the value of the command interface.

Template Parameters
TThe type of the value to be set.
Parameters
valueThe value to set.
max_triesThe maximum number of tries to set the value.
Returns
true if the value is set successfully, false otherwise.
Note
The method is thread-safe and non-blocking.
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.
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.

The documentation for this class was generated from the following file: