Go to the documentation of this file.
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...");
45 "swri::Subscriber test (manual diagnostics)",
this,
50 "swri::Subscriber test (auto diagnostics)",
this,
55 "swri::Subscriber test (value diagnostics)",
this,
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");
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)
ros::WallTimer init_timer_
const std::string & mappedTopic() const
std_msgs::Float32ConstPtr msg_
void summary(const diagnostic_msgs::DiagnosticStatus &src)
du::Updater diagnostic_updater_
void manualDiagnostics(du::DiagnosticStatusWrapper &status)
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
double timeoutMilliseconds() const
const std::string & unmappedTopic() const
double maxLatencyMicroseconds() const
void autoDiagnostics(du::DiagnosticStatusWrapper &status)
diagnostic_msgs::DiagnosticStatus DS
void valueDiagnostics(du::DiagnosticStatusWrapper &status)
void handleDiagnosticsTimer(const ros::TimerEvent &ignored)
void mergeSummary(const diagnostic_msgs::DiagnosticStatus &src)
void setHardwareID(const std::string &hwid)
void initialize(const ros::WallTimerEvent &ignored)
int numPublishers() const
double meanLatencyMicroseconds() const
void setTimeout(const ros::Duration &time_out)
void addf(const std::string &key, const char *format,...)
double minPeriodMilliseconds() const
bool timeoutEnabled() const
int main(int argc, char **argv)
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
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15