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
00113 class HeaderlessDiagnosedPublisher : public HeaderlessTopicDiagnostic
00114 {
00115 public:
00128 HeaderlessDiagnosedPublisher(const ros::Publisher &pub,
00129 diagnostic_updater::Updater &diag,
00130 const diagnostic_updater::FrequencyStatusParam &freq) :
00131 HeaderlessTopicDiagnostic(pub.getTopic(), diag, freq),
00132 publisher_(pub)
00133 {}
00134
00135 virtual ~HeaderlessDiagnosedPublisher()
00136 {}
00137
00141 virtual void publish(const ros::MessageConstPtr& message)
00142 {
00143 tick();
00144 publisher_.publish(message);
00145 }
00146
00150 virtual void publish(const ros::Message& message)
00151 {
00152 tick();
00153 publisher_.publish(message);
00154 }
00155
00159 ros::Publisher getPublisher() const
00160 {
00161 return publisher_;
00162 }
00163
00167 void setPublisher(ros::Publisher pub)
00168 {
00169 publisher_ = pub;
00170 }
00171
00172 private:
00173 ros::Publisher publisher_;
00174 };
00175
00181 class TopicDiagnostic : public HeaderlessTopicDiagnostic
00182 {
00183 public:
00199 TopicDiagnostic(
00200 std::string name,
00201 diagnostic_updater::Updater &diag,
00202 const diagnostic_updater::FrequencyStatusParam &freq,
00203 const diagnostic_updater::TimeStampStatusParam &stamp) :
00204 HeaderlessTopicDiagnostic(name, diag, freq),
00205 stamp_(stamp)
00206 {
00207 addTask(&stamp_);
00208 }
00209
00210 virtual ~TopicDiagnostic()
00211 {}
00212
00218 virtual void tick() { ROS_FATAL("tick(void) has been called on a TopicDiagnostic. This is never correct. Use tick(ros::Time &) instead."); }
00219
00226 virtual void tick(const ros::Time &stamp)
00227 {
00228 stamp_.tick(stamp);
00229 HeaderlessTopicDiagnostic::tick();
00230 }
00231
00232 private:
00233 TimeStampStatus stamp_;
00234 };
00235
00243 template<class T>
00244 class DiagnosedPublisher : public TopicDiagnostic
00245 {
00246 public:
00262 DiagnosedPublisher(const ros::Publisher &pub,
00263 diagnostic_updater::Updater &diag,
00264 const diagnostic_updater::FrequencyStatusParam &freq,
00265 const diagnostic_updater::TimeStampStatusParam &stamp) :
00266 TopicDiagnostic(pub.getTopic(), diag, freq, stamp),
00267 publisher_(pub)
00268 {}
00269
00270 virtual ~DiagnosedPublisher()
00271 {}
00272
00279 virtual void publish(const boost::shared_ptr<T>& message) {
00280 tick(message->header.stamp); publisher_.publish(message); }
00281
00288 virtual void publish(const T& message) { tick(message.header.stamp);
00289 publisher_.publish(message); }
00290
00294 ros::Publisher getPublisher() const
00295 {
00296 return publisher_;
00297 }
00298
00302 void setPublisher(ros::Publisher pub)
00303 {
00304 publisher_ = pub;
00305 }
00306
00307 private:
00308 ros::Publisher publisher_;
00309 };
00310
00311 };
00312
00313 #endif