45 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
48 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
51 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
54 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
56 const std::vector<std::string> & start_interfaces,
57 const std::vector<std::string> & stop_interfaces)
override;
59 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
60 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
62 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
63 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
65 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
66 hardware_interface::return_type
read()
override;
68 ROS2_CONTROL_DEMO_HARDWARE_PUBLIC
69 hardware_interface::return_type
write()
override;
78 std::vector<double> hw_commands_positions_;
79 std::vector<double> hw_commands_velocities_;
80 std::vector<double> hw_commands_accelerations_;
81 std::vector<double> hw_states_positions_;
82 std::vector<double> hw_states_velocities_;
83 std::vector<double> hw_states_accelerations_;
87 rclcpp::Time last_timestamp_;
88 rclcpp::Time current_timestamp;
92 enum integration_level_t : std::uint8_t
101 std::vector<integration_level_t> control_level_;
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC 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:138
ROS2_CONTROL_DEMO_HARDWARE_PUBLIC 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:30