◆ ActuatorInterface()
hardware_interface::ActuatorInterface::ActuatorInterface |
( |
const ActuatorInterface & |
other | ) |
|
|
delete |
ActuatorInterface 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_command_interfaces()
virtual std::vector<CommandInterface> hardware_interface::ActuatorInterface::export_command_interfaces |
( |
| ) |
|
|
pure virtual |
◆ export_state_interfaces()
virtual std::vector<StateInterface> hardware_interface::ActuatorInterface::export_state_interfaces |
( |
| ) |
|
|
pure virtual |
◆ get_name()
virtual std::string hardware_interface::ActuatorInterface::get_name |
( |
| ) |
const |
|
inlinevirtual |
Get name of the actuator hardware.
- Returns
- name.
◆ get_state()
const rclcpp_lifecycle::State& hardware_interface::ActuatorInterface::get_state |
( |
| ) |
const |
|
inline |
Get life-cycle state of the actuator hardware.
- Returns
- state.
◆ on_init()
◆ perform_command_mode_switch()
virtual return_type hardware_interface::ActuatorInterface::perform_command_mode_switch |
( |
const std::vector< std::string > & |
, |
|
|
const std::vector< std::string > & |
|
|
) |
| |
|
inlinevirtual |
Perform the mode-switching for the new command interface combination.
- Note
- This is part of the realtime update loop, and should be fast.
-
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
- Parameters
-
[in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
[in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
- Returns
- return_type::OK if the new command interface combination can be switched to, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
◆ prepare_command_mode_switch()
virtual return_type hardware_interface::ActuatorInterface::prepare_command_mode_switch |
( |
const std::vector< std::string > & |
, |
|
|
const std::vector< std::string > & |
|
|
) |
| |
|
inlinevirtual |
Prepare for a new command interface switch.
Prepare for any mode-switching required by the new command interface combination.
- Note
- This is a non-realtime evaluation of whether a set of command interface claims are possible, and call to start preparing data structures for the upcoming switch that will occur.
-
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
- Parameters
-
[in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
[in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
- Returns
- return_type::OK if the new command interface combination can be prepared, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
◆ read()
virtual return_type hardware_interface::ActuatorInterface::read |
( |
const rclcpp::Time & |
time, |
|
|
const rclcpp::Duration & |
period |
|
) |
| |
|
pure virtual |
Read the current state values from the actuator.
The data readings from the physical hardware has to be updated and reflected accordingly in the exported state interfaces. That is, the data pointed by the interfaces shall be updated.
- Parameters
-
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time taken by the last control loop iteration |
- Returns
- return_type::OK if the read was successful, return_type::ERROR otherwise.
Implemented in ros2_control_demo_example_6::RRBotModularJoint, and ros2_control_demo_example_14::RRBotActuatorWithoutFeedback.
◆ set_state()
void hardware_interface::ActuatorInterface::set_state |
( |
const rclcpp_lifecycle::State & |
new_state | ) |
|
|
inline |
Set life-cycle state of the actuator hardware.
- Returns
- state.
◆ write()
virtual return_type hardware_interface::ActuatorInterface::write |
( |
const rclcpp::Time & |
time, |
|
|
const rclcpp::Duration & |
period |
|
) |
| |
|
pure virtual |
The documentation for this class was generated from the following file: