![]() |
ros2_control - humble
|


Public Member Functions | |
| RangeSensor (const std::string &name) | |
| float | get_range () |
| bool | get_values_as_message (sensor_msgs::msg::Range &message) |
| Return Range message with range in meters. | |
Public Member Functions inherited from semantic_components::SemanticComponentInterface< sensor_msgs::msg::Range > | |
| SemanticComponentInterface (const std::string &name, 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 (sensor_msgs::msg::Range &) |
| Return values as MessageReturnType. | |
Additional Inherited Members | |
Protected Attributes inherited from semantic_components::SemanticComponentInterface< sensor_msgs::msg::Range > | |
| std::string | name_ |
| std::vector< std::string > | interface_names_ |
| std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > | state_interfaces_ |
|
inline |
Return Range reported by a sensor
|
inline |
Return Range message with range in meters.
Constructs and return a Range message from the current values.