◆ SensorInterface()
hardware_interface::SensorInterface::SensorInterface |
( |
const SensorInterface & |
other | ) |
|
|
delete |
SensorInterface copy constructor is actively deleted.
Hardware interfaces are having a unique ownership and thus can't be copied in order to avoid failed or simultaneous access to hardware.
◆ export_state_interfaces()
virtual std::vector<StateInterface> hardware_interface::SensorInterface::export_state_interfaces |
( |
| ) |
|
|
pure virtual |
◆ get_clock()
rclcpp::Clock::SharedPtr hardware_interface::SensorInterface::get_clock |
( |
| ) |
const |
|
inlineprotected |
◆ get_group_name()
virtual std::string hardware_interface::SensorInterface::get_group_name |
( |
| ) |
const |
|
inlinevirtual |
Get name of the actuator hardware group to which it belongs to.
- Returns
- group name.
◆ get_logger()
rclcpp::Logger hardware_interface::SensorInterface::get_logger |
( |
| ) |
const |
|
inlineprotected |
◆ get_name()
virtual std::string hardware_interface::SensorInterface::get_name |
( |
| ) |
const |
|
inlinevirtual |
Get name of the actuator hardware.
- Returns
- name.
◆ get_state()
const rclcpp_lifecycle::State& hardware_interface::SensorInterface::get_state |
( |
| ) |
const |
|
inline |
Get life-cycle state of the actuator hardware.
- Returns
- state.
◆ init()
CallbackReturn hardware_interface::SensorInterface::init |
( |
const HardwareInfo & |
hardware_info, |
|
|
rclcpp::Logger |
logger, |
|
|
rclcpp::node_interfaces::NodeClockInterface::SharedPtr |
clock_interface |
|
) |
| |
|
inline |
Initialization of the hardware interface from data parsed from the robot's URDF and also the clock and logger interfaces.
- Parameters
-
[in] | hardware_info | structure with data from URDF. |
[in] | clock_interface | pointer to the clock interface. |
[in] | logger_interface | pointer to the logger interface. |
- Returns
- CallbackReturn::SUCCESS if required data are provided and can be parsed.
-
CallbackReturn::ERROR if any error happens or data are missing.
◆ on_init()
◆ read()
virtual return_type hardware_interface::SensorInterface::read |
( |
const rclcpp::Time & |
time, |
|
|
const rclcpp::Duration & |
period |
|
) |
| |
|
pure virtual |
◆ set_state()
void hardware_interface::SensorInterface::set_state |
( |
const rclcpp_lifecycle::State & |
new_state | ) |
|
|
inline |
Set life-cycle state of the actuator hardware.
- Returns
- state.
The documentation for this class was generated from the following file: