6 #include <std_msgs/Float32.h> 7 #include <nav_msgs/Odometry.h> 12 typedef diagnostic_msgs::DiagnosticStatus
DS;
22 std_msgs::Float32ConstPtr
msg_;
31 ROS_INFO(
"Starting initialization timer...");
44 diagnostic_updater_.
add(
45 "swri::Subscriber test (manual diagnostics)",
this,
49 diagnostic_updater_.
add(
50 "swri::Subscriber test (auto diagnostics)",
this,
54 diagnostic_updater_.
add(
55 "swri::Subscriber test (value diagnostics)",
this,
65 diagnostic_updater_.
update();
70 status.
summary(DS::OK,
"No errors reported.");
84 status.
mergeSummary(DS::WARN,
"Timeouts have occurred.");
90 status.
addf(
"Topic Name",
"%s -> %s",
106 status.
addf(
"Timed Out Count",
"%d [> %f ms]",
110 status.
add(
"Timed Out Count",
"N/A");
116 status.
summary(DS::OK,
"No errors reported.");
133 status.
summary(DS::WARN,
"No message has been received.");
134 status.
add(
"Float value",
"N/A");
136 status.
summary(DS::OK,
"No errors reported.");
137 status.
addf(
"Float value",
"%f", msg_->data);
142 int main(
int argc,
char **argv)
144 ros::init(argc, argv,
"storing_subscriber_test");
void valueDiagnostics(du::DiagnosticStatusWrapper &status)
void handleDiagnosticsTimer(const ros::TimerEvent &ignored)
void summary(unsigned char lvl, const std::string s)
double meanFrequencyHz() const
void setHardwareID(const std::string &hwid)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void add(const std::string &name, TaskFunction f)
ros::WallTimer init_timer_
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
int main(int argc, char **argv)
double maxLatencyMicroseconds() const
double minPeriodMilliseconds() const
void addf(const std::string &key, const char *format,...)
du::Updater diagnostic_updater_
const std::string & unmappedTopic() const
int numPublishers() const
void manualDiagnostics(du::DiagnosticStatusWrapper &status)
void autoDiagnostics(du::DiagnosticStatusWrapper &status)
const std::string & mappedTopic() const
bool timeoutEnabled() const
diagnostic_msgs::DiagnosticStatus DS
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void initialize(const ros::WallTimerEvent &ignored)
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
void setTimeout(const ros::Duration &time_out)
std_msgs::Float32ConstPtr msg_
double meanPeriodMilliseconds() const
void mergeSummary(unsigned char lvl, const std::string s)
double timeoutMilliseconds() const
double meanLatencyMicroseconds() const
void add(const std::string &key, const T &val)
double minLatencyMicroseconds() const
double maxPeriodMilliseconds() const