Class KukaRSIHardwareInterfaceBase
Defined in File hardware_interface_rsi_base.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
Derived Types
public kuka_rsi_driver::KukaEkiRsiHardwareInterface(Class KukaEkiRsiHardwareInterface)public kuka_rsi_driver::KukaMxaRsiHardwareInterface(Class KukaMxaRsiHardwareInterface)public kuka_rsi_driver::KukaRSIHardwareInterface(Class KukaRSIHardwareInterface)
Class Documentation
-
class KukaRSIHardwareInterfaceBase : public hardware_interface::SystemInterface
Subclassed by kuka_rsi_driver::KukaEkiRsiHardwareInterface, kuka_rsi_driver::KukaMxaRsiHardwareInterface, kuka_rsi_driver::KukaRSIHardwareInterface
Public Functions
-
inline explicit KUKA_RSI_DRIVER_PUBLIC KukaRSIHardwareInterfaceBase(const std::string &logger_name)
-
virtual KUKA_RSI_DRIVER_PUBLIC ~KukaRSIHardwareInterfaceBase() = default
- KUKA_RSI_DRIVER_PUBLIC CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override
- KUKA_RSI_DRIVER_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces () override
- KUKA_RSI_DRIVER_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces () override
- KUKA_RSI_DRIVER_PUBLIC CallbackReturn on_cleanup (const rclcpp_lifecycle::State &) override
- KUKA_RSI_DRIVER_PUBLIC return_type read (const rclcpp::Time &, const rclcpp::Duration &) override
- KUKA_RSI_DRIVER_PUBLIC return_type write (const rclcpp::Time &, const rclcpp::Duration &) override
- KUKA_RSI_DRIVER_PUBLIC void set_server_event (kuka_drivers_core::HardwareEvent)
- KUKA_RSI_DRIVER_PUBLIC void initialize_command_interfaces (kuka_drivers_core::ControlMode control_mode, RsiCycleTime cycle_time)
Protected Functions
- KUKA_RSI_DRIVER_LOCAL bool SetupRobot (kuka::external::control::kss::Configuration &config, std::unique_ptr< kuka::external::control::EventHandler > event_handler, std::unique_ptr< kuka::external::control::kss::IEventHandlerExtension > extension)
- virtual KUKA_RSI_DRIVER_LOCAL void Read (const int64_t request_timeout)
- KUKA_RSI_DRIVER_LOCAL void Write ()
- KUKA_RSI_DRIVER_LOCAL bool CheckJointInterfaces (const hardware_interface::ComponentInfo &joint) const
- KUKA_RSI_DRIVER_LOCAL void CopyGPIOStatesToCommands ()
- virtual KUKA_RSI_DRIVER_LOCAL void CreateRobotInstance (const kuka::external::control::kss::Configuration &)=0
- KUKA_RSI_DRIVER_LOCAL kuka::external::control::kss::GPIOConfiguration ParseGPIOConfig (const hardware_interface::InterfaceInfo &info)
-
CallbackReturn extended_activation(const rclcpp_lifecycle::State&)
-
CallbackReturn extended_deactivation(const rclcpp_lifecycle::State&)
-
kuka::external::control::Status ChangeCycleTime()
Protected Attributes
-
const rclcpp::Logger logger_
-
std::unique_ptr<kuka::external::control::kss::rsi::Robot> robot_ptr_
-
std::vector<double> hw_states_
-
std::vector<double> hw_gpio_states_
-
std::vector<double> hw_commands_
-
std::vector<double> hw_gpio_commands_
-
double server_state_
-
kuka_drivers_core::HardwareEvent last_event_ = kuka_drivers_core::HardwareEvent::HARDWARE_EVENT_UNSPECIFIED
-
std::mutex event_mutex_
-
std::vector<int> gpio_states_to_commands_map_
-
bool is_active_
-
bool msg_received_
-
StatusManager status_manager_
-
double hw_control_mode_command_
-
double cycle_time_command_
-
kuka_drivers_core::ControlMode prev_control_mode_ = kuka_drivers_core::ControlMode::CONTROL_MODE_UNSPECIFIED
-
RsiCycleTime prev_cycle_time_ = RsiCycleTime::RSI_12MS
Protected Static Attributes
-
static constexpr std::chrono::milliseconds IDLE_SLEEP_DURATION = {2}
-
static constexpr std::chrono::milliseconds INIT_WAIT_DURATION = {100}
-
static constexpr std::chrono::seconds DRIVES_POWERED_TIMEOUT = {3}
-
static constexpr std::chrono::milliseconds DRIVES_POWERED_CHECK_INTERVAL = {100}
-
static constexpr int64_t READ_TIMEOUT_MS = 1'000
-
struct InitSequenceReport
-
inline explicit KUKA_RSI_DRIVER_PUBLIC KukaRSIHardwareInterfaceBase(const std::string &logger_name)