Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef __DIAGNOSTIC_UPDATER__DRIVER_H__
00037 #define __DIAGNOSTIC_UPDATER__DRIVER_H__
00038
00039 #include <ros/publisher.h>
00040 #include <ros/subscription.h>
00041 #include <diagnostic_updater/update_functions.h>
00042
00043 namespace diagnostic_updater
00044 {
00045
00055 class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
00056 {
00057 public:
00070 HeaderlessTopicDiagnostic(
00071 std::string name,
00072 diagnostic_updater::Updater &diag,
00073 const diagnostic_updater::FrequencyStatusParam &freq) :
00074 CompositeDiagnosticTask(name + " topic status"),
00075 freq_(freq)
00076 {
00077 addTask(&freq_);
00078 diag.add(*this);
00079 }
00080
00081 virtual ~HeaderlessTopicDiagnostic()
00082 {}
00083
00088 virtual void tick()
00089 {
00090 freq_.tick();
00091 }
00092
00097 virtual void clear_window()
00098 {
00099 freq_.clear();
00100 }
00101
00102 private:
00103 diagnostic_updater::FrequencyStatus freq_;
00104 };
00105
00111 class TopicDiagnostic : public HeaderlessTopicDiagnostic
00112 {
00113 public:
00129 TopicDiagnostic(
00130 std::string name,
00131 diagnostic_updater::Updater &diag,
00132 const diagnostic_updater::FrequencyStatusParam &freq,
00133 const diagnostic_updater::TimeStampStatusParam &stamp) :
00134 HeaderlessTopicDiagnostic(name, diag, freq),
00135 stamp_(stamp)
00136 {
00137 addTask(&stamp_);
00138 }
00139
00140 virtual ~TopicDiagnostic()
00141 {}
00142
00148 virtual void tick() { ROS_FATAL("tick(void) has been called on a TopicDiagnostic. This is never correct. Use tick(ros::Time &) instead."); }
00149
00156 virtual void tick(const ros::Time &stamp)
00157 {
00158 stamp_.tick(stamp);
00159 HeaderlessTopicDiagnostic::tick();
00160 }
00161
00162 private:
00163 TimeStampStatus stamp_;
00164 };
00165
00173 template<class T>
00174 class DiagnosedPublisher : public TopicDiagnostic
00175 {
00176 public:
00192 DiagnosedPublisher(const ros::Publisher &pub,
00193 diagnostic_updater::Updater &diag,
00194 const diagnostic_updater::FrequencyStatusParam &freq,
00195 const diagnostic_updater::TimeStampStatusParam &stamp) :
00196 TopicDiagnostic(pub.getTopic(), diag, freq, stamp),
00197 publisher_(pub)
00198 {}
00199
00200 virtual ~DiagnosedPublisher()
00201 {}
00202
00209 virtual void publish(const boost::shared_ptr<T>& message) {
00210 tick(message->header.stamp); publisher_.publish(message); }
00211
00218 virtual void publish(const T& message) { tick(message.header.stamp);
00219 publisher_.publish(message); }
00220
00224 ros::Publisher getPublisher() const
00225 {
00226 return publisher_;
00227 }
00228
00232 void setPublisher(ros::Publisher pub)
00233 {
00234 publisher_ = pub;
00235 }
00236
00237 private:
00238 ros::Publisher publisher_;
00239 };
00240
00241 };
00242
00243 #endif