15 #ifndef ETHERCAT_DRIVER__ETHERCAT_DRIVER_HPP_
16 #define ETHERCAT_DRIVER__ETHERCAT_DRIVER_HPP_
18 #include <unordered_map>
22 #include <pluginlib/class_loader.hpp>
23 #include "hardware_interface/handle.hpp"
24 #include "hardware_interface/hardware_info.hpp"
25 #include "hardware_interface/system_interface.hpp"
26 #include "hardware_interface/types/hardware_interface_return_values.hpp"
27 #include "rclcpp/macros.hpp"
28 #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
29 #include "rclcpp_lifecycle/state.hpp"
63 hardware_interface::return_type
read(
const rclcpp::Time &,
const rclcpp::Duration &)
override;
66 hardware_interface::return_type
write(
const rclcpp::Time &,
const rclcpp::Duration &)
override;
69 std::vector<std::unordered_map<std::string, std::string>> getEcModuleParam(
70 std::string & urdf, std::string component_name, std::string component_type);
72 std::vector<std::shared_ptr<ethercat_interface::EcSlave>> ec_modules_;
73 std::vector<std::unordered_map<std::string, std::string>> ec_module_parameters_;
75 std::vector<std::vector<double>> hw_joint_commands_;
76 std::vector<std::vector<double>> hw_sensor_commands_;
77 std::vector<std::vector<double>> hw_gpio_commands_;
78 std::vector<std::vector<double>> hw_joint_states_;
79 std::vector<std::vector<double>> hw_sensor_states_;
80 std::vector<std::vector<double>> hw_gpio_states_;
82 pluginlib::ClassLoader<ethercat_interface::EcSlave> ec_loader_{
83 "ethercat_interface",
"ethercat_interface::EcSlave"};
85 int control_frequency_;
Definition: ethercat_driver.hpp:40
ETHERCAT_DRIVER_PUBLIC CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
ETHERCAT_DRIVER_PUBLIC hardware_interface::return_type read(const rclcpp::Time &, const rclcpp::Duration &) override
ETHERCAT_DRIVER_PUBLIC CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
ETHERCAT_DRIVER_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
ETHERCAT_DRIVER_PUBLIC hardware_interface::return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
ETHERCAT_DRIVER_PUBLIC CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
ETHERCAT_DRIVER_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces() override
ETHERCAT_DRIVER_PUBLIC CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
Definition: ec_master.hpp:32
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Definition: ethercat_driver.hpp:34
Definition: ethercat_driver.hpp:37
#define ETHERCAT_DRIVER_PUBLIC
Definition: visibility_control.h:43