00001 00009 /***************************************************************************** 00010 ** Ifdefs 00011 *****************************************************************************/ 00012 00013 #ifndef KOBUKI_NODE_DIAGNOSTICS_HPP_ 00014 #define KOBUKI_NODE_DIAGNOSTICS_HPP_ 00015 00016 /***************************************************************************** 00017 ** Includes 00018 *****************************************************************************/ 00019 00020 #include <kobuki_driver/packets/cliff.hpp> 00021 #include <kobuki_driver/modules/battery.hpp> 00022 #include <kobuki_driver/packets/core_sensors.hpp> 00023 #include <diagnostic_updater/diagnostic_updater.h> 00024 00025 /***************************************************************************** 00026 ** Namespaces 00027 *****************************************************************************/ 00028 00029 namespace kobuki { 00030 00031 /***************************************************************************** 00032 ** Interfaces 00033 *****************************************************************************/ 00034 00035 00039 class BatteryTask : public diagnostic_updater::DiagnosticTask { 00040 public: 00041 BatteryTask() : DiagnosticTask("Battery") {} 00042 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00043 void update(const Battery &battery) { status = battery; } 00044 00045 private: 00046 Battery status; 00047 }; 00048 00052 class WatchdogTask : public diagnostic_updater::DiagnosticTask { 00053 public: 00054 WatchdogTask() : DiagnosticTask("Watchdog"), alive(false) {} 00055 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00056 void update(const bool &is_alive) { alive = is_alive; } 00057 bool isAlive() const { return alive; } 00058 00059 private: 00060 bool alive; 00061 }; 00062 00066 class CliffSensorTask : public diagnostic_updater::DiagnosticTask { 00067 public: 00068 CliffSensorTask() : DiagnosticTask("Cliff Sensor") {} 00069 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00070 void update(const uint8_t &new_status, const Cliff::Data &new_values) { 00071 status = new_status; values = new_values; 00072 } 00073 00074 private: 00075 uint8_t status; 00076 Cliff::Data values; 00077 }; 00078 00082 class WallSensorTask : public diagnostic_updater::DiagnosticTask { 00083 public: 00084 WallSensorTask() : DiagnosticTask("Wall Sensor") {} 00085 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00086 void update(const uint8_t &new_status) { status = new_status; } 00087 00088 private: 00089 uint8_t status; 00090 }; 00091 00095 class WheelDropTask : public diagnostic_updater::DiagnosticTask { 00096 public: 00097 WheelDropTask() : DiagnosticTask("Wheel Drop") {} 00098 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00099 void update(const uint8_t &new_status) { status = new_status; } 00100 00101 private: 00102 uint8_t status; 00103 }; 00104 00109 class MotorCurrentTask : public diagnostic_updater::DiagnosticTask { 00110 public: 00111 MotorCurrentTask() : DiagnosticTask("Motor Current") {} 00112 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00113 void update(const std::vector<uint8_t> &new_values) { values = new_values; } 00114 00115 private: 00116 std::vector<uint8_t> values; 00117 }; 00118 00122 class MotorStateTask : public diagnostic_updater::DiagnosticTask { 00123 public: 00124 MotorStateTask() : DiagnosticTask("Motor State") {} 00125 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00126 void update(bool new_state) { state = new_state; }; 00127 00128 private: 00129 bool state; 00130 }; 00131 00135 class GyroSensorTask : public diagnostic_updater::DiagnosticTask { 00136 public: 00137 GyroSensorTask() : DiagnosticTask("Gyro Sensor") {} 00138 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00139 void update(int16_t new_heading) { heading = new_heading; } 00140 00141 private: 00142 int16_t heading; 00143 }; 00144 00148 class DigitalInputTask : public diagnostic_updater::DiagnosticTask { 00149 public: 00150 DigitalInputTask() : DiagnosticTask("Digital Input") {} 00151 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00152 void update(uint16_t new_status) { status = new_status; } 00153 00154 private: 00155 uint16_t status; 00156 }; 00157 00161 class AnalogInputTask : public diagnostic_updater::DiagnosticTask { 00162 public: 00163 AnalogInputTask() : DiagnosticTask("Analog Input") {} 00164 void run(diagnostic_updater::DiagnosticStatusWrapper &stat); 00165 void update(const std::vector<uint16_t> &new_values) { values = new_values; } 00166 00167 private: 00168 std::vector<uint16_t> values; 00169 }; 00170 00171 } // namespace kobuki 00172 00173 #endif /* KOBUKI_NODE_DIAGNOSTICS_HPP_ */