|
| System (std::unique_ptr< SystemInterface > impl) |
|
| System (System &&other) noexcept |
|
const rclcpp_lifecycle::State & | initialize (const HardwareInfo &system_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface) |
|
const rclcpp_lifecycle::State & | configure () |
|
const rclcpp_lifecycle::State & | cleanup () |
|
const rclcpp_lifecycle::State & | shutdown () |
|
const rclcpp_lifecycle::State & | activate () |
|
const rclcpp_lifecycle::State & | deactivate () |
|
const rclcpp_lifecycle::State & | error () |
|
std::vector< StateInterface::ConstSharedPtr > | export_state_interfaces () |
|
std::vector< CommandInterface::SharedPtr > | export_command_interfaces () |
|
return_type | prepare_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) |
|
return_type | perform_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) |
|
std::string | get_name () const |
|
std::string | get_group_name () const |
|
const rclcpp_lifecycle::State & | get_lifecycle_state () const |
|
const rclcpp::Time & | get_last_read_time () const |
|
const rclcpp::Time & | get_last_write_time () const |
|
return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period) |
|
return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period) |
|
std::recursive_mutex & | get_mutex () |
|
The documentation for this class was generated from the following files:
- ros2_control/hardware_interface/include/hardware_interface/system.hpp
- ros2_control/hardware_interface/src/system.cpp