latched_subscriber_test.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 
5 
6 #include <std_msgs/Float32.h>
7 #include <nav_msgs/Odometry.h>
8 
9 namespace du = diagnostic_updater;
10 
11 // Alias type for easier access to DiagnosticStatus enumerations.
12 typedef diagnostic_msgs::DiagnosticStatus DS;
13 
15 {
19 
21 
23 
24  public:
26  {
27  // Setup a one-shot timer to initialize the node after a brief
28  // delay so that /rosout is always fully initialized.
29  ROS_INFO("Starting initialization timer...");
32  this,
33  true);
34  }
35 
36  void initialize(const ros::WallTimerEvent &ignored)
37  {
39  sub_.initialize(nh_, "odom");
40 
43  "swri::Subscriber test (manual diagnostics)", this,
45 
48  "swri::Subscriber test (auto diagnostics)", this,
50 
53  "swri::Subscriber test (value diagnostics)", this,
55 
58  this);
59  }
60 
62  {
64  }
65 
67  {
68  status.summary(DS::OK, "No errors reported.");
69 
70  // The swri::Subscriber provides methods to access all of the
71  // statistics and status information. These are suitable for
72  // making control decisions or report diagnostics. In this
73  // example, we access the data directly to update a diagnostic
74  // status on our own. This is useful if you want to apply custom
75  // summary semantics or change how the key/values are included.
76 
77  if (sub_.messageCount() == 0) {
78  status.mergeSummary(DS::WARN, "No messages received.");
79  } else if (sub_.inTimeout()) {
80  status.mergeSummary(DS::ERROR, "Topic has timed out.");
81  } else if (sub_.timeoutCount() > 0) {
82  status.mergeSummary(DS::WARN, "Timeouts have occurred.");
83  }
84 
85  if (sub_.mappedTopic() == sub_.unmappedTopic()) {
86  status.addf("Topic Name", "%s", sub_.mappedTopic().c_str());
87  } else {
88  status.addf("Topic Name", "%s -> %s",
89  sub_.unmappedTopic().c_str(),
90  sub_.mappedTopic().c_str());
91  }
92  status.addf("Number of publishers", "%d", sub_.numPublishers());
93 
94  status.addf("Mean Latency [us]", "%f", sub_.meanLatencyMicroseconds());
95  status.addf("Min Latency [us]", "%f", sub_.minLatencyMicroseconds());
96  status.addf("Max Latency [us]", "%f", sub_.maxLatencyMicroseconds());
97 
98  status.addf("Mean Frequency [Hz]", "%f", sub_.meanFrequencyHz());
99  status.addf("Mean Period [ms]", "%f", sub_.meanPeriodMilliseconds());
100  status.addf("Min Period [ms]", "%f", sub_.minPeriodMilliseconds());
101  status.addf("Max Period [ms]", "%f", sub_.maxPeriodMilliseconds());
102 
103  if (sub_.timeoutEnabled()) {
104  status.addf("Timed Out Count", "%d [> %f ms]",
105  sub_.timeoutCount(),
107  } else {
108  status.add("Timed Out Count", "N/A");
109  }
110  }
111 
113  {
114  status.summary(DS::OK, "No errors reported.");
115 
116  // In this example, we use swri::Subscriber's appendDiagnostics
117  // method to include diagnostics using a common format and common
118  // summary semantics. If we didn't care about specific bits of
119  // information, we can leave them out by removing specific flags.
120  sub_.appendDiagnostics(status, "Odometry",
126  }
127 
129  {
130  if (!sub_.messageCount()) {
131  status.summary(DS::WARN, "No message has been received.");
132  status.add("Float value", "N/A");
133  } else {
134  status.summary(DS::OK, "No errors reported.");
135  if (sub_.data()) {
136  status.addf("Float value (data())", "%f", sub_.data()->data);
137  } else {
138  ROS_ERROR("no data?!");
139  }
140 
141  status.addf("Float value (->)", "%f", sub_->data);
142  }
143  }
144 }; // class LatchedSubscriberTest
145 
146 int main(int argc, char **argv)
147 {
148  ros::init(argc, argv, "latched_subscriber_test");
149 
151  ros::spin();
152 
153  return 0;
154 }
LatchedSubscriberTest::handleDiagnosticsTimer
void handleDiagnosticsTimer(const ros::TimerEvent &ignored)
Definition: latched_subscriber_test.cpp:61
swri::LatchedSubscriber::initialize
void initialize(ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints())
Definition: latched_subscriber.h:93
LatchedSubscriberTest::init_timer_
ros::WallTimer init_timer_
Definition: latched_subscriber_test.cpp:17
swri::Subscriber::maxPeriodMilliseconds
double maxPeriodMilliseconds() const
Definition: subscriber.h:406
swri::Subscriber::meanPeriodMilliseconds
double meanPeriodMilliseconds() const
Definition: subscriber.h:394
LatchedSubscriberTest::nh_
ros::NodeHandle nh_
Definition: latched_subscriber_test.cpp:16
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
swri::Subscriber::meanFrequencyHz
double meanFrequencyHz() const
Definition: subscriber.h:376
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
swri::LatchedSubscriber< std_msgs::Float32 >
ros.h
LatchedSubscriberTest::initialize
void initialize(const ros::WallTimerEvent &ignored)
Definition: latched_subscriber_test.cpp:36
LatchedSubscriberTest
Definition: latched_subscriber_test.cpp:14
swri::Subscriber::mappedTopic
const std::string & mappedTopic() const
Definition: subscriber.h:288
ros::WallTimer
diagnostic_updater::Updater
diagnostic_updater.h
LatchedSubscriberTest::LatchedSubscriberTest
LatchedSubscriberTest()
Definition: latched_subscriber_test.cpp:25
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
DS
diagnostic_msgs::DiagnosticStatus DS
Definition: latched_subscriber_test.cpp:12
LatchedSubscriberTest::diag_timer_
ros::Timer diag_timer_
Definition: latched_subscriber_test.cpp:18
swri::Subscriber::timeoutCount
int timeoutCount()
Definition: subscriber.h:471
diagnostic_updater
swri::Subscriber::appendDiagnostics
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
Definition: subscriber.h:477
swri::Subscriber::timeoutMilliseconds
double timeoutMilliseconds() const
Definition: subscriber.h:459
swri::Subscriber::unmappedTopic
const std::string & unmappedTopic() const
Definition: subscriber.h:282
swri::Subscriber::maxLatencyMicroseconds
double maxLatencyMicroseconds() const
Definition: subscriber.h:364
LatchedSubscriberTest::sub_
swri::LatchedSubscriber< std_msgs::Float32 > sub_
Definition: latched_subscriber_test.cpp:22
swri::Subscriber::DIAG_CONNECTION
@ DIAG_CONNECTION
Definition: subscriber.h:182
LatchedSubscriberTest::manualDiagnostics
void manualDiagnostics(du::DiagnosticStatusWrapper &status)
Definition: latched_subscriber_test.cpp:66
swri::Subscriber::DIAG_MSG_COUNT
@ DIAG_MSG_COUNT
Definition: subscriber.h:183
ros::TimerEvent
swri::Subscriber::messageCount
int messageCount() const
Definition: subscriber.h:306
swri::LatchedSubscriber::data
const boost::shared_ptr< M const > & data() const
Definition: latched_subscriber.h:111
main
int main(int argc, char **argv)
Definition: latched_subscriber_test.cpp:146
diagnostic_updater::DiagnosticStatusWrapper::mergeSummary
void mergeSummary(const diagnostic_msgs::DiagnosticStatus &src)
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
LatchedSubscriberTest::autoDiagnostics
void autoDiagnostics(du::DiagnosticStatusWrapper &status)
Definition: latched_subscriber_test.cpp:112
swri::Subscriber::inTimeout
bool inTimeout()
Definition: subscriber.h:465
latched_subscriber.h
diagnostic_updater::Updater::update
void update()
ros::WallTimerEvent
LatchedSubscriberTest::diagnostic_updater_
du::Updater diagnostic_updater_
Definition: latched_subscriber_test.cpp:20
swri::Subscriber::DIAG_RATE
@ DIAG_RATE
Definition: subscriber.h:186
swri::Subscriber::numPublishers
int numPublishers() const
Definition: subscriber.h:294
swri::Subscriber::meanLatencyMicroseconds
double meanLatencyMicroseconds() const
Definition: subscriber.h:352
swri::Subscriber::DIAG_LATENCY
@ DIAG_LATENCY
Definition: subscriber.h:185
LatchedSubscriberTest::valueDiagnostics
void valueDiagnostics(du::DiagnosticStatusWrapper &status)
Definition: latched_subscriber_test.cpp:128
swri::Subscriber::setTimeout
void setTimeout(const ros::Duration &time_out)
Definition: subscriber.h:412
ROS_ERROR
#define ROS_ERROR(...)
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
diagnostic_updater::DiagnosticStatusWrapper
ros::spin
ROSCPP_DECL void spin()
swri::Subscriber::minPeriodMilliseconds
double minPeriodMilliseconds() const
Definition: subscriber.h:400
ros::WallDuration
swri::Subscriber::timeoutEnabled
bool timeoutEnabled() const
Definition: subscriber.h:453
ROS_INFO
#define ROS_INFO(...)
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
swri::Subscriber::minLatencyMicroseconds
double minLatencyMicroseconds() const
Definition: subscriber.h:358
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::NodeHandle::createWallTimer
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Timer
swri::Subscriber::DIAG_TIMEOUT
@ DIAG_TIMEOUT
Definition: subscriber.h:184
ros::NodeHandle


swri_roscpp
Author(s): P. J. Reed
autogenerated on Thu Jun 6 2024 02:33:09