Go to the documentation of this file.
23 #include <boost/thread/mutex.hpp>
37 ros::param::param<int>(
"~window_size", window_size, std::ceil(hz));
71 for(
size_t i=0; i<
topics_.size(); i++)
94 std::vector< GenericTopicDiagnostic* >
tasks_;
100 int main(
int argc,
char **argv)
102 ros::init(argc, argv,
"topic_status_monitor");
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool get(const std::string &key, bool &b)
std::vector< std::string > topics_
ros::Subscriber generic_sub_
void updateDiagnostics(const ros::TimerEvent &event)
int main(int argc, char **argv)
diagnostic_updater::Updater diagnostic_updater_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Timer diagnostic_timer_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > topic_diagnostic_task_
void setHardwareID(const std::string &hwid)
void topicCallback(const topic_tools::ShapeShifter::ConstPtr &msg)
GenericTopicDiagnostic(std::string &topic_name, diagnostic_updater::Updater &diagnostic_updater)
std::vector< GenericTopicDiagnostic * > tasks_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
cob_monitoring
Author(s): Florian Weisshardt
, Felix Messmer
autogenerated on Fri Aug 2 2024 09:45:52