Go to the documentation of this file. 1 #include <boost/bind.hpp>
4 #include <boost/bind.hpp>
8 #include <std_msgs/Float32.h>
9 #include <nav_msgs/Odometry.h>
14 typedef diagnostic_msgs::DiagnosticStatus
DS;
31 ROS_INFO(
"Starting initialization timer...");
53 "swri::Subscriber test (manual diagnostics)",
this,
57 "swri::Subscriber test (auto diagnostics)",
this,
77 status.
summary(DS::OK,
"No errors reported.");
91 status.
mergeSummary(DS::WARN,
"Timeouts have occurred.");
97 status.
addf(
"Topic Name",
"%s -> %s",
113 status.
addf(
"Timed Out Count",
"%d [> %f ms]",
117 status.
add(
"Timed Out Count",
"N/A");
123 status.
summary(DS::OK,
"No errors reported.");
138 int main(
int argc,
char **argv)
140 ros::init(argc, argv,
"subscriber_test");
double maxPeriodMilliseconds() const
double meanPeriodMilliseconds() const
void add(const std::string &key, const bool &b)
double meanFrequencyHz() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void handleMessage(const nav_msgs::OdometryConstPtr &msg)
du::Updater diagnostic_updater_
ros::WallTimer init_timer_
const std::string & mappedTopic() const
int main(int argc, char **argv)
void summary(const diagnostic_msgs::DiagnosticStatus &src)
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
double timeoutMilliseconds() const
const std::string & unmappedTopic() const
double maxLatencyMicroseconds() const
diagnostic_msgs::DiagnosticStatus DS
void handleDiagnosticsTimer(const ros::TimerEvent &ignored)
void mergeSummary(const diagnostic_msgs::DiagnosticStatus &src)
void setHardwareID(const std::string &hwid)
void manualDiagnostics(du::DiagnosticStatusWrapper &status)
int numPublishers() const
double meanLatencyMicroseconds() const
void setTimeout(const ros::Duration &time_out)
void autoDiagnostics(du::DiagnosticStatusWrapper &status)
void addf(const std::string &key, const char *format,...)
double minPeriodMilliseconds() const
bool timeoutEnabled() const
void add(const std::string &name, TaskFunction f)
double minLatencyMicroseconds() const
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void initialize(const ros::WallTimerEvent &ignored)
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
#define ROS_INFO_THROTTLE(period,...)
swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15