15 #ifndef ROS2_CONTROL_DEMO_EXAMPLE_3__RRBOT_SYSTEM_MULTI_INTERFACE_HPP_
16 #define ROS2_CONTROL_DEMO_EXAMPLE_3__RRBOT_SYSTEM_MULTI_INTERFACE_HPP_
24 #include "hardware_interface/handle.hpp"
25 #include "hardware_interface/hardware_info.hpp"
26 #include "hardware_interface/system_interface.hpp"
27 #include "hardware_interface/types/hardware_interface_return_values.hpp"
28 #include "rclcpp/clock.hpp"
29 #include "rclcpp/duration.hpp"
30 #include "rclcpp/macros.hpp"
31 #include "rclcpp/time.hpp"
32 #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
33 #include "rclcpp_lifecycle/state.hpp"
35 namespace ros2_control_demo_example_3
46 const rclcpp_lifecycle::State & previous_state)
override;
49 const std::vector<std::string> & start_interfaces,
50 const std::vector<std::string> & stop_interfaces)
override;
53 const rclcpp_lifecycle::State & previous_state)
override;
56 const rclcpp_lifecycle::State & previous_state)
override;
58 hardware_interface::return_type
read(
59 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
61 hardware_interface::return_type
write(
62 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
72 enum integration_level_t : std::uint8_t
81 std::vector<integration_level_t> control_level_;
Definition: system_interface.hpp:82
Definition: rrbot_system_multi_interface.hpp:38
hardware_interface::return_type prepare_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Prepare for a new command interface switch.
Definition: rrbot_system_multi_interface.cpp:123
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: rrbot_system_multi_interface.cpp:31
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition: rrbot_system_multi_interface.cpp:230
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the actuator.
Definition: rrbot_system_multi_interface.cpp:278
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:76
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170