Skip to content

File hw_monitor_wrapper.hpp

File List > include > nebula_ros > velodyne > hw_monitor_wrapper.hpp

Go to the documentation of this file

// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include "nebula_ros/common/parameter_descriptors.hpp"

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <nebula_common/velodyne/velodyne_common.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>

#include <boost/algorithm/string/join.hpp>
#include <boost/asio.hpp>
#include <boost/lexical_cast.hpp>
#include <boost/property_tree/ptree.hpp>

#include <array>
#include <memory>
#include <string>
#include <tuple>

namespace nebula
{
namespace ros
{
class VelodyneHwMonitorWrapper
{
public:
  VelodyneHwMonitorWrapper(
    rclcpp::Node * const parent_node,
    const std::shared_ptr<nebula::drivers::VelodyneHwInterface> & hw_interface,
    std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & config);

  void OnConfigChange(
    const std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & /* new_config */)
  {
  }

  nebula::Status Status();

private:
  void InitializeVelodyneDiagnostics();

  void OnVelodyneStatusTimer();

  void OnVelodyneSnapshotTimer();

  void OnVelodyneDiagnosticsTimer();

  std::string GetPtreeValue(
    std::shared_ptr<boost::property_tree::ptree> pt, std::mutex & mtx_pt, const std::string & key);

  std::string GetFixedPrecisionString(double val, int pre = 2);

  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopHv();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopAdTemp();  // only32
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopLm20Temp();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopPwr5v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopPwr25v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopPwr33v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopPwr5vRaw();  // only16
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopPwrRaw();  // only32
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetTopPwrVccint();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotIOut();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotPwr12v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotLm20Temp();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotPwr5v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotPwr25v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotPwr33v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotPwrVIn();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetBotPwr125v();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetVhv();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetAdcNf();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetAdcStats();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetIxe();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetAdctpStat();

  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetGpsPpsState();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetGpsPosition();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetMotorState();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetMotorRpm();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetMotorLock();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetMotorPhase();
  std::tuple<bool, uint8_t, std::string, std::string> VelodyneGetLaserState();

  void VelodyneCheckTopHv(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopAdTemp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopLm20Temp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopPwr5v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopPwr25v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopPwr33v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopPwrRaw(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTopPwrVccint(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotIOut(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotPwr12v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotLm20Temp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotPwr5v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotPwr25v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotPwr33v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotPwrVIn(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckBotPwr125v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckVhv(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckAdcNf(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckAdcStats(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckIxe(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckAdctpStat(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  rclcpp::TimerBase::SharedPtr diagnostics_status_timer_;
  std::shared_ptr<boost::property_tree::ptree> current_status_tree;
  void VelodyneCheckGpsPpsState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckGpsPosition(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckMotorState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckMotorRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckMotorLock(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckMotorPhase(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckLaserState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);

  void VelodyneCheckSnapshot(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);

  void VelodyneCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckPps(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);
  void VelodyneCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics);

  rclcpp::Logger logger_;
  diagnostic_updater::Updater diagnostics_updater_;
  nebula::Status status_;

  const std::shared_ptr<nebula::drivers::VelodyneHwInterface> hw_interface_;
  rclcpp::Node * const parent_node_;

  std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> sensor_configuration_;

  uint16_t diag_span_;
  bool show_advanced_diagnostics_;

  rclcpp::TimerBase::SharedPtr diagnostics_snapshot_timer_;
  rclcpp::TimerBase::SharedPtr diagnostics_update_timer_;
  rclcpp::TimerBase::SharedPtr diagnostics_diag_timer_;

  std::shared_ptr<std::string> current_snapshot;
  std::shared_ptr<boost::property_tree::ptree> current_snapshot_tree;
  std::shared_ptr<boost::property_tree::ptree> current_diag_tree;
  std::shared_ptr<rclcpp::Time> current_snapshot_time;
  uint8_t current_diag_status;

  std::mutex mtx_snapshot_;
  std::mutex mtx_status_;
  std::mutex mtx_diag_;

  std::string info_model_;
  std::string info_serial_;

  static constexpr auto key_volt_temp_top_hv = "volt_temp.top.hv";
  static constexpr auto key_volt_temp_top_ad_temp = "volt_temp.top.ad_temp";  // only32
  static constexpr auto key_volt_temp_top_lm20_temp = "volt_temp.top.lm20_temp";
  static constexpr auto key_volt_temp_top_pwr_5v = "volt_temp.top.pwr_5v";
  static constexpr auto key_volt_temp_top_pwr_2_5v = "volt_temp.top.pwr_2_5v";
  static constexpr auto key_volt_temp_top_pwr_3_3v = "volt_temp.top.pwr_3_3v";
  static constexpr auto key_volt_temp_top_pwr_5v_raw = "volt_temp.top.pwr_5v_raw";  // only16
  static constexpr auto key_volt_temp_top_pwr_raw = "volt_temp.top.pwr_raw";        // only32
  static constexpr auto key_volt_temp_top_pwr_vccint = "volt_temp.top.pwr_vccint";
  static constexpr auto key_volt_temp_bot_i_out = "volt_temp.bot.i_out";
  static constexpr auto key_volt_temp_bot_pwr_1_2v = "volt_temp.bot.pwr_1_2v";
  static constexpr auto key_volt_temp_bot_lm20_temp = "volt_temp.bot.lm20_temp";
  static constexpr auto key_volt_temp_bot_pwr_5v = "volt_temp.bot.pwr_5v";
  static constexpr auto key_volt_temp_bot_pwr_2_5v = "volt_temp.bot.pwr_2_5v";
  static constexpr auto key_volt_temp_bot_pwr_3_3v = "volt_temp.bot.pwr_3_3v";
  static constexpr auto key_volt_temp_bot_pwr_v_in = "volt_temp.bot.pwr_v_in";
  static constexpr auto key_volt_temp_bot_pwr_1_25v = "volt_temp.bot.pwr_1_25v";
  static constexpr auto key_vhv = "vhv";
  static constexpr auto key_adc_nf = "adc_nf";
  static constexpr auto key_adc_stats = "adc_stats";
  static constexpr auto key_ixe = "ixe";
  static constexpr auto key_adctp_stat = "adctp_stat";
  static constexpr auto key_status_gps_pps_state = "gps.pps_state";
  static constexpr auto key_status_gps_pps_position = "gps.position";
  static constexpr auto key_status_motor_state = "motor.state";
  static constexpr auto key_status_motor_rpm = "motor.rpm";
  static constexpr auto key_status_motor_lock = "motor.lock";
  static constexpr auto key_status_motor_phase = "motor.phase";
  static constexpr auto key_status_laser_state = "laser.state";

  static constexpr auto name_volt_temp_top_hv = "Top HV";
  static constexpr auto name_volt_temp_top_ad_temp = "Top A/D TD";
  static constexpr auto name_volt_temp_top_lm20_temp = "Top Temp";
  static constexpr auto name_volt_temp_top_pwr_5v = "Top 5v";
  static constexpr auto name_volt_temp_top_pwr_2_5v = "Top 2.5v";
  static constexpr auto name_volt_temp_top_pwr_3_3v = "Top 3.3v";
  static constexpr auto name_volt_temp_top_pwr_5v_raw = "Top 5v(RAW)";
  static constexpr auto name_volt_temp_top_pwr_raw = "Top RAW";
  static constexpr auto name_volt_temp_top_pwr_vccint = "Top VCCINT";
  static constexpr auto name_volt_temp_bot_i_out = "Bot I out";
  static constexpr auto name_volt_temp_bot_pwr_1_2v = "Bot 1.2v";
  static constexpr auto name_volt_temp_bot_lm20_temp = "Bot Temp";
  static constexpr auto name_volt_temp_bot_pwr_5v = "Bot 5v";
  static constexpr auto name_volt_temp_bot_pwr_2_5v = "Bot 2.5v";
  static constexpr auto name_volt_temp_bot_pwr_3_3v = "Bot 3.3v";
  static constexpr auto name_volt_temp_bot_pwr_v_in = "Bot V in";
  static constexpr auto name_volt_temp_bot_pwr_1_25v = "Bot 1.25v";  // N/A?
  static constexpr auto name_vhv = "VHV";
  static constexpr auto name_adc_nf = "adc_nf";
  static constexpr auto name_adc_stats = "adc_stats";
  static constexpr auto name_ixe = "ixe";
  static constexpr auto name_adctp_stat = "adctp_stat";
  static constexpr auto name_status_gps_pps_state = "GPS PPS";
  static constexpr auto name_status_gps_pps_position = "GPS Position";
  static constexpr auto name_status_motor_state = "Motor State";
  static constexpr auto name_status_motor_rpm = "Motor RPM";
  static constexpr auto name_status_motor_lock = "Motor Lock";
  static constexpr auto name_status_motor_phase = "Motor Phase";
  static constexpr auto name_status_laser_state = "Laser State";

  const std::string message_sep{": "};
  static constexpr auto not_supported_message = "Not supported";
  static constexpr auto error_message = "Error";

  static constexpr auto key_info_model = "info.model";
  static constexpr auto key_info_serial = "info.serial";

  static constexpr auto temperature_cold_message = "temperature cold";
  static constexpr auto temperature_hot_message = "temperature hot";

  static constexpr auto voltage_low_message = "voltage low";
  static constexpr auto voltage_high_message = "voltage high";

  static constexpr auto ampere_low_message = "ampere low";
  static constexpr auto ampere_high_message = "ampere high";
};
}  // namespace ros
}  // namespace nebula