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

Public Types

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

Public Member Functions

 LoanedStateInterface (const StateInterface &state_interface)
 
 LoanedStateInterface (const StateInterface &state_interface, Deleter &&deleter)
 
 LoanedStateInterface (StateInterface::ConstSharedPtr state_interface)
 
 LoanedStateInterface (StateInterface::ConstSharedPtr state_interface, Deleter &&deleter)
 
 LoanedStateInterface (const LoanedStateInterface &other)=delete
 
 LoanedStateInterface (LoanedStateInterface &&other)=default
 
const std::string & get_name () const
 
const std::string & get_interface_name () const
 
const std::string & get_prefix_name () const
 
double get_value () const
 
template<typename T = double>
std::optional< T > get_optional (unsigned int max_tries=10) const
 Get the value of the state interface.
 
HandleDataType get_data_type () const
 Get the data type of the state interface.
 
bool is_castable_to_double () const
 Check if the state interface can be casted to double.
 

Protected Attributes

const StateInterfacestate_interface_
 
Deleter deleter_
 

Member Function Documentation

◆ get_data_type()

HandleDataType hardware_interface::LoanedStateInterface::get_data_type ( ) const
inline

Get the data type of the state interface.

Returns
The data type of the state interface.

◆ get_optional()

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

Get the value of the state interface.

Template Parameters
TThe type of the value to be retrieved.
Returns
The value of the state 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.

◆ is_castable_to_double()

bool hardware_interface::LoanedStateInterface::is_castable_to_double ( ) const
inline

Check if the state interface can be casted to double.

Returns
True if the state interface can be casted to double, false otherwise.

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