|
| 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.
|
|
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.
|
|
bool | get_values (std::vector< double > &values) const |
| Return all values.
|
|
bool | get_values_as_message (MessageReturnType &) |
| Return values as MessageReturnType.
|
|
◆ assign_loaned_state_interfaces()
template<typename MessageReturnType >
Assign loaned state interfaces from the hardware.
Assign loaned state interfaces on the controller start.
- Parameters
-
[in] | state_interfaces | vector of interfaces provided by the controller. |
◆ get_state_interface_names()
template<typename MessageReturnType >
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 >
Return all values.
- Returns
- true if it gets all the values, else false
◆ get_values_as_message()
template<typename MessageReturnType >
Return values as MessageReturnType.
- Returns
- false by default
The documentation for this class was generated from the following file: