node_monitor.h
Go to the documentation of this file.
1 // Monitors a single node process
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #ifndef ROSMON_MONITOR_NODE_MONITOR_H
5 #define ROSMON_MONITOR_NODE_MONITOR_H
6 
7 #include "../launch/node.h"
8 #include "../fd_watcher.h"
9 
10 #include <ros/node_handle.h>
11 
12 #include <boost/signals2.hpp>
13 #include <boost/circular_buffer.hpp>
14 
15 namespace rosmon
16 {
17 
18 namespace monitor
19 {
20 
25 {
26 public:
27  typedef std::shared_ptr<NodeMonitor> Ptr;
28  typedef std::shared_ptr<NodeMonitor> ConstPtr;
29 
31  enum State
32  {
37  };
38 
47  launch::Node::ConstPtr launchNode,
48  FDWatcher::Ptr fdWatcher, ros::NodeHandle& nh);
49  ~NodeMonitor();
50 
52 
53 
55  void start();
56 
58  void stop(bool restart = false);
59 
61  void restart();
62 
68  void shutdown();
69 
75  void forceExit();
76 
78  bool running() const;
79 
81  State state() const;
83 
85 
86 
88  inline bool coredumpAvailable() const
89  { return !m_debuggerCommand.empty(); }
90 
96  inline std::string debuggerCommand() const
97  { return m_debuggerCommand; }
98 
108  void launchDebugger();
110 
112 
113 
114  void beginStatUpdate();
115  void addCPUTime(uint64_t userTime, uint64_t systemTime);
116  void addMemory(uint64_t memoryBytes);
117  void endStatUpdate(uint64_t elapsedTime);
118 
125  inline double userLoad() const
126  { return m_userLoad; }
127 
134  inline double systemLoad() const
135  { return m_systemLoad; }
136 
145  inline double memory() const
146  { return m_memory; }
147 
148  inline unsigned int restartCount() const
149  { return m_restartCount; }
150 
151  inline uint64_t memoryLimit()const
152  { return m_launchNode->memoryLimitByte();}
153 
154  inline float cpuLimit()const
155  { return m_launchNode->cpuLimit();}
156 
158 
160  inline std::string name() const
161  { return m_launchNode->name(); }
162 
164  inline std::string namespaceString() const
165  { return m_launchNode->namespaceString(); }
166 
168  inline int pid() const
169  { return m_pid; }
170 
172  inline double stopTimeout() const
173  { return m_launchNode->stopTimeout(); }
174 
180  boost::signals2::signal<void(std::string,std::string)> logMessageSignal;
181 
183  boost::signals2::signal<void(std::string)> exitedSignal;
184 private:
185  enum Command
186  {
190  };
191 
192  std::vector<std::string> composeCommand() const;
193 
194  void communicate();
195 
196  template<typename... Args>
197  void log(const char* format, const Args& ... args);
198  void checkStop();
199  void gatherCoredump(int signal);
200 
202 
204 
205  boost::circular_buffer<char> m_rxBuffer;
206 
207  int m_pid = -1;
208  int m_fd = -1;
210 
213 
215 
217 
218  std::string m_debuggerCommand;
219 
220  unsigned int m_restartCount = 0;
221 
222  uint64_t m_userTime = 0;
223  uint64_t m_systemTime = 0;
224  double m_userLoad = 0.0;
225  double m_systemLoad = 0.0;
226  uint64_t m_memory = 0;
227 
230 };
231 
232 }
233 
234 }
235 
236 #endif
std::shared_ptr< const Node > ConstPtr
Definition: node.h:24
boost::signals2::signal< void(std::string)> exitedSignal
Signalled whenever the process exits.
Definition: node_monitor.h:183
void start()
Start the node.
void forceExit()
Finish shutdown sequence.
double stopTimeout() const
Node stop timeout.
Definition: node_monitor.h:172
double userLoad() const
Estimate of the userspace load.
Definition: node_monitor.h:125
Monitors a single node process.
Definition: node_monitor.h:24
void addMemory(uint64_t memoryBytes)
void stop(bool restart=false)
Stop the node.
boost::circular_buffer< char > m_rxBuffer
Definition: node_monitor.h:205
std::shared_ptr< NodeMonitor > ConstPtr
Definition: node_monitor.h:28
unsigned int restartCount() const
Definition: node_monitor.h:148
double systemLoad() const
Estimate of the kernelspace load.
Definition: node_monitor.h:134
std::string m_processWorkingDirectory
Definition: node_monitor.h:228
bool coredumpAvailable() const
Is a core dump available from a crash under rosmon control?
Definition: node_monitor.h:88
NodeMonitor(launch::Node::ConstPtr launchNode, FDWatcher::Ptr fdWatcher, ros::NodeHandle &nh)
Constructor.
void addCPUTime(uint64_t userTime, uint64_t systemTime)
Idle (e.g. exited with code 0)
Definition: node_monitor.h:33
std::string namespaceString() const
Node namespace.
Definition: node_monitor.h:164
void gatherCoredump(int signal)
void launchDebugger()
Launch gdb interactively.
Waiting for automatic restart after crash.
Definition: node_monitor.h:36
void log(const char *format, const Args &...args)
int pid() const
Node PID.
Definition: node_monitor.h:168
uint64_t memoryLimit() const
Definition: node_monitor.h:151
std::string debuggerCommand() const
What command should we use to debug the coredump?
Definition: node_monitor.h:96
ros::WallTimer m_stopCheckTimer
Definition: node_monitor.h:211
void shutdown()
Start shutdown sequence.
bool running() const
Is the node running?
std::vector< std::string > composeCommand() const
void endStatUpdate(uint64_t elapsedTime)
launch::Node::ConstPtr m_launchNode
Definition: node_monitor.h:201
Crashed (i.e. exited with code != 0)
Definition: node_monitor.h:35
State state() const
Get process state.
boost::signals2::signal< void(std::string, std::string)> logMessageSignal
Logging signal.
Definition: node_monitor.h:180
void restart()
Restart the node.
std::string name() const
Node name.
Definition: node_monitor.h:160
double memory() const
Total system memory used by the node.
Definition: node_monitor.h:145
std::shared_ptr< NodeMonitor > Ptr
Definition: node_monitor.h:27


rosmon_core
Author(s): Max Schwarz
autogenerated on Wed Jul 10 2019 03:10:12