Class HardwareComponent
- Defined in File hardware_component.hpp 
Class Documentation
- 
class HardwareComponent
- Public Functions - 
HardwareComponent() = default
 - 
explicit HardwareComponent(std::unique_ptr<HardwareComponentInterface> impl)
 - 
explicit HardwareComponent(HardwareComponent &&other) noexcept
 - 
~HardwareComponent() = default
 - 
HardwareComponent(const HardwareComponent &other) = delete
 - 
HardwareComponent &operator=(const HardwareComponent &other) = delete
 - 
HardwareComponent &operator=(HardwareComponent &&other) = delete
 - 
const rclcpp_lifecycle::State &initialize(const hardware_interface::HardwareComponentParams ¶ms)
 - 
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)
 - 
const std::string &get_name() const
 - 
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
 - 
const HardwareComponentStatisticsCollector &get_read_statistics() const
 - 
const HardwareComponentStatisticsCollector &get_write_statistics() 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()
 
- 
HardwareComponent() = default