40 hardware_interface::CallbackReturn
on_init(
43 hardware_interface::CallbackReturn on_configure(
44 const rclcpp_lifecycle::State & previous_state)
override;
46 hardware_interface::CallbackReturn on_activate(
47 const rclcpp_lifecycle::State & previous_state)
override;
49 hardware_interface::CallbackReturn on_deactivate(
50 const rclcpp_lifecycle::State & previous_state)
override;
52 hardware_interface::return_type
read(
53 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
55 hardware_interface::return_type
write(
56 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
59 control_msgs::msg::HardwareStatus & msg_template)
override;
62 control_msgs::msg::HardwareStatus & msg)
override;
70 std::shared_ptr<diagnostic_updater::Updater> updater_;
71 void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat);
73 rclcpp::Executor::WeakPtr executor_;
74 rclcpp::Node::SharedPtr custom_status_node_;
75 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr custom_status_publisher_;
76 rclcpp::TimerBase::SharedPtr custom_status_timer_;