diff --git a/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp index 86fa28ca3..afbe7bd2e 100644 --- a/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp @@ -265,7 +265,6 @@ class VelodyneHwMonitorWrapper rclcpp::Logger logger_; diagnostic_updater::Updater diagnostics_updater_; - nebula::Status status_; const std::shared_ptr hw_interface_; rclcpp::Node * const parent_node_; @@ -275,8 +274,6 @@ class VelodyneHwMonitorWrapper uint16_t diag_span_; bool show_advanced_diagnostics_; - rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; - rclcpp::TimerBase::SharedPtr diagnostics_diag_timer_; std::shared_ptr current_diag_tree_; diff --git a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp index cd63c523c..1da852ec0 100644 --- a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp @@ -19,7 +19,6 @@ VelodyneHwMonitorWrapper::VelodyneHwMonitorWrapper( : logger_(parent_node->get_logger().get_child("HwMonitor")), diagnostics_updater_( (parent_node->declare_parameter("diagnostic_updater.use_fqn", true), parent_node)), - status_(Status::OK), hw_interface_(hw_interface), parent_node_(parent_node), sensor_configuration_(config)