topic_status_monitor.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <ros/ros.h>
23 #include <boost/thread/mutex.hpp>
24 #include <cmath>
25 
26 
28 {
29 public:
31  {
32  ros::NodeHandle nh;
33  double hz, hzerror;
34  int window_size;
35  ros::param::get("~hz", hz);
36  ros::param::get("~hzerror", hzerror);
37  ros::param::param<int>("~window_size", window_size, std::ceil(hz));
38 
39  min_freq_ = hz-hzerror;
40  max_freq_ = hz+hzerror;
41 
42  diagnostic_updater::FrequencyStatusParam freq_param(&min_freq_, &max_freq_, 0.0, window_size); //min_freq, max_freq, tolerance (default: 0.1), window_size (default: 5)
43  diagnostic_updater::TimeStampStatusParam stamp_param(-1, 1); //min_acceptable (default: -1), max_acceptable (default: 5)
44 
45  topic_diagnostic_task_.reset(new diagnostic_updater::TopicDiagnostic(topic_name, diagnostic_updater, freq_param, stamp_param));
46 
48  }
49 
51  {
53  }
54 
58 };
59 
60 
62 {
63 public:
65  {
66  ros::NodeHandle nh;
67  ros::param::get("~topics", topics_);
68  ros::param::get("~diagnostics_name", hardware_id_);
70 
71  for(size_t i=0; i<topics_.size(); i++)
72  {
74  }
75 
78  }
79 
81  {}
82 
83 
85  {
87  }
88 
89 private:
90  std::string hardware_id_;
91  std::vector<std::string> topics_;
93 
94  std::vector< GenericTopicDiagnostic* > tasks_;
96 };
97 
98 
99 
100 int main(int argc, char **argv)
101 {
102  ros::init(argc, argv, "topic_status_monitor");
103  TopicStatusMonitor tsm;
104 
105  ros::spin();
106 
107  return 0;
108 }
boost::shared_ptr< ShapeShifter const >
diagnostic_updater::TimeStampStatusParam
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
ros.h
TopicStatusMonitor::topics_
std::vector< std::string > topics_
Definition: topic_status_monitor.cpp:91
TopicStatusMonitor::~TopicStatusMonitor
~TopicStatusMonitor()
Definition: topic_status_monitor.cpp:80
GenericTopicDiagnostic::min_freq_
double min_freq_
Definition: topic_status_monitor.cpp:55
TopicStatusMonitor::hardware_id_
std::string hardware_id_
Definition: topic_status_monitor.cpp:90
diagnostic_updater::Updater
TopicStatusMonitor
Definition: topic_status_monitor.cpp:61
publisher.h
GenericTopicDiagnostic::generic_sub_
ros::Subscriber generic_sub_
Definition: topic_status_monitor.cpp:56
diagnostic_updater.h
TopicStatusMonitor::updateDiagnostics
void updateDiagnostics(const ros::TimerEvent &event)
Definition: topic_status_monitor.cpp:84
GenericTopicDiagnostic
Definition: topic_status_monitor.cpp:27
main
int main(int argc, char **argv)
Definition: topic_status_monitor.cpp:100
diagnostic_updater
TopicStatusMonitor::diagnostic_updater_
diagnostic_updater::Updater diagnostic_updater_
Definition: topic_status_monitor.cpp:92
TopicStatusMonitor::TopicStatusMonitor
TopicStatusMonitor()
Definition: topic_status_monitor.cpp:64
ros::NodeHandle::subscribe
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())
TopicStatusMonitor::diagnostic_timer_
ros::Timer diagnostic_timer_
Definition: topic_status_monitor.cpp:95
GenericTopicDiagnostic::topic_diagnostic_task_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > topic_diagnostic_task_
Definition: topic_status_monitor.cpp:57
ros::TimerEvent
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
shape_shifter.h
diagnostic_updater::TopicDiagnostic
diagnostic_updater::Updater::update
void update()
update_functions.h
GenericTopicDiagnostic::topicCallback
void topicCallback(const topic_tools::ShapeShifter::ConstPtr &msg)
Definition: topic_status_monitor.cpp:50
GenericTopicDiagnostic::GenericTopicDiagnostic
GenericTopicDiagnostic(std::string &topic_name, diagnostic_updater::Updater &diagnostic_updater)
Definition: topic_status_monitor.cpp:30
ros::spin
ROSCPP_DECL void spin()
TopicStatusMonitor::tasks_
std::vector< GenericTopicDiagnostic * > tasks_
Definition: topic_status_monitor.cpp:94
GenericTopicDiagnostic::max_freq_
double max_freq_
Definition: topic_status_monitor.cpp:55
topic_tools::ShapeShifter
ros::Timer::start
void start()
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
diagnostic_updater::FrequencyStatusParam


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Fri Aug 2 2024 09:45:52