36 const int UNDERVOLT_ERROR = 18;
37 const int UNDERVOLT_WARN = 19;
38 const int OVERVOLT_ERROR = 30;
39 const int OVERVOLT_WARN = 29;
40 const int DRIVER_OVERTEMP_ERROR = 50;
41 const int DRIVER_OVERTEMP_WARN = 30;
42 const int MOTOR_OVERTEMP_ERROR = 80;
43 const int MOTOR_OVERTEMP_WARN = 70;
44 const double LOWPOWER_ERROR = 0.2;
45 const double LOWPOWER_WARN = 0.3;
46 const int CONTROLFREQ_WARN = 90;
47 const unsigned int SAFETY_TIMEOUT = 0x1;
48 const unsigned int SAFETY_LOCKOUT = 0x2;
49 const unsigned int SAFETY_ESTOP = 0x8;
50 const unsigned int SAFETY_CCI = 0x10;
51 const unsigned int SAFETY_PSU = 0x20;
52 const unsigned int SAFETY_CURRENT = 0x40;
53 const unsigned int SAFETY_WARN = (SAFETY_TIMEOUT | SAFETY_CCI | SAFETY_PSU);
54 const unsigned int SAFETY_ERROR = (SAFETY_LOCKOUT | SAFETY_ESTOP | SAFETY_CURRENT);
63 DiagnosticTask(
"system_status"),
72 msg_.uptime = system_status->getUptime();
74 msg_.battery_voltage = system_status->getVoltage(0);
75 msg_.left_driver_voltage = system_status->getVoltage(1);
76 msg_.right_driver_voltage = system_status->getVoltage(2);
78 msg_.mcu_and_user_port_current = system_status->getCurrent(0);
79 msg_.left_driver_current = system_status->getCurrent(1);
80 msg_.right_driver_current = system_status->getCurrent(2);
82 msg_.left_driver_temp = system_status->getTemperature(0);
83 msg_.right_driver_temp = system_status->getTemperature(1);
84 msg_.left_motor_temp = system_status->getTemperature(2);
85 msg_.right_motor_temp = system_status->getTemperature(3);
87 stat.
add(
"Uptime",
msg_.uptime);
89 stat.
add(
"Battery Voltage",
msg_.battery_voltage);
90 stat.
add(
"Left Motor Driver Voltage",
msg_.left_driver_voltage);
91 stat.
add(
"Right Motor Driver Voltage",
msg_.right_driver_voltage);
93 stat.
add(
"MCU and User Port Current",
msg_.mcu_and_user_port_current);
94 stat.
add(
"Left Motor Driver Current",
msg_.left_driver_current);
95 stat.
add(
"Right Motor Driver Current",
msg_.right_driver_current);
97 stat.
add(
"Left Motor Driver Temp (C)",
msg_.left_driver_temp);
98 stat.
add(
"Right Motor Driver Temp (C)",
msg_.right_driver_temp);
99 stat.
add(
"Left Motor Temp (C)",
msg_.left_motor_temp);
100 stat.
add(
"Right Motor Temp (C)",
msg_.right_motor_temp);
102 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"System Status OK");
103 if (
msg_.battery_voltage > OVERVOLT_ERROR)
105 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Main battery voltage too high");
107 else if (
msg_.battery_voltage > OVERVOLT_WARN)
109 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN,
"Main battery voltage too high");
111 else if (
msg_.battery_voltage < UNDERVOLT_ERROR)
113 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Main battery voltage too low");
115 else if (
msg_.battery_voltage < UNDERVOLT_WARN)
117 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN,
"Main battery voltage too low");
121 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::OK,
"Voltage OK");
124 if (std::max(
msg_.left_driver_temp,
msg_.right_driver_temp) > DRIVER_OVERTEMP_ERROR)
126 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Motor drivers too hot");
128 else if (std::max(
msg_.left_driver_temp,
msg_.right_driver_temp) > DRIVER_OVERTEMP_WARN)
130 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN,
"Motor drivers too hot");
132 else if (std::max(
msg_.left_motor_temp,
msg_.right_motor_temp) > MOTOR_OVERTEMP_ERROR)
134 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Motors too hot");
136 else if (std::max(
msg_.left_motor_temp,
msg_.right_motor_temp) > MOTOR_OVERTEMP_WARN)
138 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN,
"Motors too hot");
142 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::OK,
"Temperature OK");
158 msg_.charge_estimate = power_status->getChargeEstimate(0);
159 msg_.capacity_estimate = power_status->getCapacityEstimate(0);
161 stat.
add(
"Charge (%)",
msg_.charge_estimate);
162 stat.
add(
"Battery Capacity (Wh)",
msg_.capacity_estimate);
164 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Power System OK");
165 if (
msg_.charge_estimate < LOWPOWER_ERROR)
167 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Low power");
169 else if (
msg_.charge_estimate < LOWPOWER_WARN)
171 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN,
"Low power");
175 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::OK,
"Charge OK");
181 husky_msgs::HuskyStatus &msg)
192 uint16_t flags = safety_status->getFlags();
193 msg_.timeout = (flags & SAFETY_TIMEOUT) > 0;
194 msg_.lockout = (flags & SAFETY_LOCKOUT) > 0;
195 msg_.e_stop = (flags & SAFETY_ESTOP) > 0;
196 msg_.ros_pause = (flags & SAFETY_CCI) > 0;
197 msg_.no_battery = (flags & SAFETY_PSU) > 0;
198 msg_.current_limit = (flags & SAFETY_CURRENT) > 0;
200 stat.
add(
"Timeout", static_cast<bool>(
msg_.timeout));
201 stat.
add(
"Lockout", static_cast<bool>(
msg_.lockout));
202 stat.
add(
"Emergency Stop", static_cast<bool>(
msg_.e_stop));
203 stat.
add(
"ROS Pause", static_cast<bool>(
msg_.ros_pause));
204 stat.
add(
"No battery", static_cast<bool>(
msg_.no_battery));
205 stat.
add(
"Current limit", static_cast<bool>(
msg_.current_limit));
207 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Safety System OK");
208 if ((flags & SAFETY_ERROR) > 0)
210 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Safety System Error");
212 else if ((flags & SAFETY_WARN) > 0)
214 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN,
"Safety System Warning");
222 target_control_freq_(target_control_freq)
236 stat.
add(
"ROS Control Loop Frequency",
msg_.ros_control_loop_freq);
240 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Software OK");
241 if (margin < CONTROLFREQ_WARN)
244 message <<
"Control loop executing " << 100 -
static_cast<int>(margin) <<
"% slower than desired";
245 stat.
mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, message.str());
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
HuskyHardwareDiagnosticTask(husky_msgs::HuskyStatus &msg)
void summary(unsigned char lvl, const std::string s)
void update(diagnostic_updater::DiagnosticStatusWrapper &stat, typename horizon_legacy::Channel< T >::Ptr &status)
void updateControlFrequency(double frequency)
husky_msgs::HuskyStatus & msg_
def message(msg, args, kwargs)
void mergeSummary(unsigned char lvl, const std::string s)
DiagnosticTask(const std::string name)
double target_control_freq_
void add(const std::string &key, const T &val)
husky_msgs::HuskyStatus & msg_
HuskySoftwareDiagnosticTask(husky_msgs::HuskyStatus &msg, double target_control_freq)