00001 
00032 #include "husky_base/husky_diagnostics.h"
00033 
00034 namespace
00035 {
00036   const int UNDERVOLT_ERROR = 18;
00037   const int UNDERVOLT_WARN = 19;
00038   const int OVERVOLT_ERROR = 30;
00039   const int OVERVOLT_WARN = 29;
00040   const int DRIVER_OVERTEMP_ERROR = 50;
00041   const int DRIVER_OVERTEMP_WARN = 30;
00042   const int MOTOR_OVERTEMP_ERROR = 80;
00043   const int MOTOR_OVERTEMP_WARN = 70;
00044   const double LOWPOWER_ERROR = 0.2;
00045   const double LOWPOWER_WARN = 0.3;
00046   const int CONTROLFREQ_WARN = 90;
00047   const unsigned int SAFETY_TIMEOUT = 0x1;
00048   const unsigned int SAFETY_LOCKOUT = 0x2;
00049   const unsigned int SAFETY_ESTOP = 0x8;
00050   const unsigned int SAFETY_CCI = 0x10;
00051   const unsigned int SAFETY_PSU = 0x20;
00052   const unsigned int SAFETY_CURRENT = 0x40;
00053   const unsigned int SAFETY_WARN = (SAFETY_TIMEOUT | SAFETY_CCI | SAFETY_PSU);
00054   const unsigned int SAFETY_ERROR = (SAFETY_LOCKOUT | SAFETY_ESTOP | SAFETY_CURRENT);
00055 }  
00056 
00057 namespace husky_base
00058 {
00059 
00060   template<>
00061   HuskyHardwareDiagnosticTask<clearpath::DataSystemStatus>::HuskyHardwareDiagnosticTask(husky_msgs::HuskyStatus &msg)
00062     :
00063     DiagnosticTask("system_status"),
00064     msg_(msg)
00065   { }
00066 
00067   template<>
00068   void HuskyHardwareDiagnosticTask<clearpath::DataSystemStatus>::update(
00069     diagnostic_updater::DiagnosticStatusWrapper &stat,
00070     horizon_legacy::Channel<clearpath::DataSystemStatus>::Ptr &system_status)
00071   {
00072     msg_.uptime = system_status->getUptime();
00073 
00074     msg_.battery_voltage = system_status->getVoltage(0);
00075     msg_.left_driver_voltage = system_status->getVoltage(1);
00076     msg_.right_driver_voltage = system_status->getVoltage(2);
00077 
00078     msg_.mcu_and_user_port_current = system_status->getCurrent(0);
00079     msg_.left_driver_current = system_status->getCurrent(1);
00080     msg_.right_driver_current = system_status->getCurrent(2);
00081 
00082     msg_.left_driver_temp = system_status->getTemperature(0);
00083     msg_.right_driver_temp = system_status->getTemperature(1);
00084     msg_.left_motor_temp = system_status->getTemperature(2);
00085     msg_.right_motor_temp = system_status->getTemperature(3);
00086 
00087     stat.add("Uptime", msg_.uptime);
00088 
00089     stat.add("Battery Voltage", msg_.battery_voltage);
00090     stat.add("Left Motor Driver Voltage", msg_.left_driver_voltage);
00091     stat.add("Right Motor Driver Voltage", msg_.right_driver_voltage);
00092 
00093     stat.add("MCU and User Port Current", msg_.mcu_and_user_port_current);
00094     stat.add("Left Motor Driver Current", msg_.left_driver_current);
00095     stat.add("Right Motor Driver Current", msg_.right_driver_current);
00096 
00097     stat.add("Left Motor Driver Temp (C)", msg_.left_driver_temp);
00098     stat.add("Right Motor Driver Temp (C)", msg_.right_driver_temp);
00099     stat.add("Left Motor Temp (C)", msg_.left_motor_temp);
00100     stat.add("Right Motor Temp (C)", msg_.right_motor_temp);
00101 
00102     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "System Status OK");
00103     if (msg_.battery_voltage > OVERVOLT_ERROR)
00104     {
00105       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Main battery voltage too high");
00106     }
00107     else if (msg_.battery_voltage > OVERVOLT_WARN)
00108     {
00109       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Main battery voltage too high");
00110     }
00111     else if (msg_.battery_voltage < UNDERVOLT_ERROR)
00112     {
00113       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Main battery voltage too low");
00114     }
00115     else if (msg_.battery_voltage < UNDERVOLT_WARN)
00116     {
00117       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Main battery voltage too low");
00118     }
00119     else
00120     {
00121       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::OK, "Voltage OK");
00122     }
00123 
00124     if (std::max(msg_.left_driver_temp, msg_.right_driver_temp) > DRIVER_OVERTEMP_ERROR)
00125     {
00126       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Motor drivers too hot");
00127     }
00128     else if (std::max(msg_.left_driver_temp, msg_.right_driver_temp) > DRIVER_OVERTEMP_WARN)
00129     {
00130       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Motor drivers too hot");
00131     }
00132     else if (std::max(msg_.left_motor_temp, msg_.right_motor_temp) > MOTOR_OVERTEMP_ERROR)
00133     {
00134       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Motors too hot");
00135     }
00136     else if (std::max(msg_.left_motor_temp, msg_.right_motor_temp) > MOTOR_OVERTEMP_WARN)
00137     {
00138       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Motors too hot");
00139     }
00140     else
00141     {
00142       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::OK, "Temperature OK");
00143     }
00144   }
00145 
00146   template<>
00147   HuskyHardwareDiagnosticTask<clearpath::DataPowerSystem>::HuskyHardwareDiagnosticTask(husky_msgs::HuskyStatus &msg)
00148     :
00149     DiagnosticTask("power_status"),
00150     msg_(msg)
00151   { }
00152 
00153   template<>
00154   void HuskyHardwareDiagnosticTask<clearpath::DataPowerSystem>::update(
00155     diagnostic_updater::DiagnosticStatusWrapper &stat,
00156     horizon_legacy::Channel<clearpath::DataPowerSystem>::Ptr &power_status)
00157   {
00158     msg_.charge_estimate = power_status->getChargeEstimate(0);
00159     msg_.capacity_estimate = power_status->getCapacityEstimate(0);
00160 
00161     stat.add("Charge (%)", msg_.charge_estimate);
00162     stat.add("Battery Capacity (Wh)", msg_.capacity_estimate);
00163 
00164     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Power System OK");
00165     if (msg_.charge_estimate < LOWPOWER_ERROR)
00166     {
00167       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Low power");
00168     }
00169     else if (msg_.charge_estimate < LOWPOWER_WARN)
00170     {
00171       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Low power");
00172     }
00173     else
00174     {
00175       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::OK, "Charge OK");
00176     }
00177   }
00178 
00179   template<>
00180   HuskyHardwareDiagnosticTask<clearpath::DataSafetySystemStatus>::HuskyHardwareDiagnosticTask(
00181     husky_msgs::HuskyStatus &msg)
00182     :
00183     DiagnosticTask("safety_status"),
00184     msg_(msg)
00185   { }
00186 
00187   template<>
00188   void HuskyHardwareDiagnosticTask<clearpath::DataSafetySystemStatus>::update(
00189     diagnostic_updater::DiagnosticStatusWrapper &stat,
00190     horizon_legacy::Channel<clearpath::DataSafetySystemStatus>::Ptr &safety_status)
00191   {
00192     uint16_t flags = safety_status->getFlags();
00193     msg_.timeout = (flags & SAFETY_TIMEOUT) > 0;
00194     msg_.lockout = (flags & SAFETY_LOCKOUT) > 0;
00195     msg_.e_stop = (flags & SAFETY_ESTOP) > 0;
00196     msg_.ros_pause = (flags & SAFETY_CCI) > 0;
00197     msg_.no_battery = (flags & SAFETY_PSU) > 0;
00198     msg_.current_limit = (flags & SAFETY_CURRENT) > 0;
00199 
00200     stat.add("Timeout", static_cast<bool>(msg_.timeout));
00201     stat.add("Lockout", static_cast<bool>(msg_.lockout));
00202     stat.add("Emergency Stop", static_cast<bool>(msg_.e_stop));
00203     stat.add("ROS Pause", static_cast<bool>(msg_.ros_pause));
00204     stat.add("No battery", static_cast<bool>(msg_.no_battery));
00205     stat.add("Current limit", static_cast<bool>(msg_.current_limit));
00206 
00207     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Safety System OK");
00208     if ((flags & SAFETY_ERROR) > 0)
00209     {
00210       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Safety System Error");
00211     }
00212     else if ((flags & SAFETY_WARN) > 0)
00213     {
00214       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Safety System Warning");
00215     }
00216   }
00217 
00218   HuskySoftwareDiagnosticTask::HuskySoftwareDiagnosticTask(husky_msgs::HuskyStatus &msg, double target_control_freq)
00219     :
00220     DiagnosticTask("software_status"),
00221     msg_(msg),
00222     target_control_freq_(target_control_freq)
00223   {
00224     reset();
00225   }
00226 
00227   void HuskySoftwareDiagnosticTask::updateControlFrequency(double frequency)
00228   {
00229     
00230     control_freq_ = std::min(control_freq_, frequency);
00231   }
00232 
00233   void HuskySoftwareDiagnosticTask::run(diagnostic_updater::DiagnosticStatusWrapper &stat)
00234   {
00235     msg_.ros_control_loop_freq = control_freq_;
00236     stat.add("ROS Control Loop Frequency", msg_.ros_control_loop_freq);
00237 
00238     double margin = control_freq_ / target_control_freq_ * 100;
00239 
00240     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Software OK");
00241     if (margin < CONTROLFREQ_WARN)
00242     {
00243       std::ostringstream message;
00244       message << "Control loop executing " << 100 - static_cast<int>(margin) << "% slower than desired";
00245       stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, message.str());
00246     }
00247 
00248     reset();
00249   }
00250 
00251   void HuskySoftwareDiagnosticTask::reset()
00252   {
00253     control_freq_ = std::numeric_limits<double>::infinity();
00254     target_control_freq_ = 0;
00255   }
00256 }