ros2_control - rolling
Public Member Functions | Protected Attributes | List of all members
semantic_components::SemanticComponentInterface< MessageReturnType > Class Template Reference

Public Member Functions

 SemanticComponentInterface (const std::string &name, const std::vector< std::string > &interface_names)
 
 SemanticComponentInterface (const std::string &name, std::size_t size=0)
 
bool assign_loaned_state_interfaces (std::vector< hardware_interface::LoanedStateInterface > &state_interfaces)
 Assign loaned state interfaces from the hardware. More...
 
void release_interfaces ()
 Release loaned interfaces from the hardware.
 
virtual std::vector< std::string > get_state_interface_names ()
 Definition of state interface names for the component. More...
 
bool get_values (std::vector< double > &values) const
 Return all values. More...
 
bool get_values_as_message (MessageReturnType &)
 Return values as MessageReturnType. More...
 

Protected Attributes

std::string name_
 
std::vector< std::string > interface_names_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > state_interfaces_
 

Member Function Documentation

◆ assign_loaned_state_interfaces()

template<typename MessageReturnType >
bool semantic_components::SemanticComponentInterface< MessageReturnType >::assign_loaned_state_interfaces ( std::vector< hardware_interface::LoanedStateInterface > &  state_interfaces)
inline

Assign loaned state interfaces from the hardware.

Assign loaned state interfaces on the controller start.

Parameters
[in]state_interfacesvector of interfaces provided by the controller.

◆ get_state_interface_names()

template<typename MessageReturnType >
virtual std::vector<std::string> semantic_components::SemanticComponentInterface< MessageReturnType >::get_state_interface_names ( )
inlinevirtual

Definition of state interface names for the component.

The function should be used in "state_interface_configuration()" of a controller to provide standardized interface names semantic component.

\default Default implementation defined state interfaces as "name/NR" where NR is number from 0 to size of values;

Returns
list of strings with state interface names for the semantic component.

◆ get_values()

template<typename MessageReturnType >
bool semantic_components::SemanticComponentInterface< MessageReturnType >::get_values ( std::vector< double > &  values) const
inline

Return all values.

Returns
true if it gets all the values, else false

◆ get_values_as_message()

template<typename MessageReturnType >
bool semantic_components::SemanticComponentInterface< MessageReturnType >::get_values_as_message ( MessageReturnType &  )
inline

Return values as MessageReturnType.

Returns
false by default

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