23 #include <boost/thread/mutex.hpp> 37 ros::param::param<int>(
"~window_size", window_size, std::ceil(hz));
69 diagnostic_updater_.setHardwareID(hardware_id_);
71 for(
size_t i=0; i<topics_.size(); i++)
77 diagnostic_timer_.
start();
86 diagnostic_updater_.update();
94 std::vector< GenericTopicDiagnostic* >
tasks_;
100 int main(
int argc,
char **argv)
102 ros::init(argc, argv,
"topic_status_monitor");
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > topic_diagnostic_task_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
GenericTopicDiagnostic(std::string &topic_name, diagnostic_updater::Updater &diagnostic_updater)
diagnostic_updater::Updater diagnostic_updater_
void topicCallback(const topic_tools::ShapeShifter::ConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
void updateDiagnostics(const ros::TimerEvent &event)
ros::Timer diagnostic_timer_
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
std::vector< GenericTopicDiagnostic * > tasks_
ros::Subscriber generic_sub_
std::vector< std::string > topics_