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 #include "../log_event.h"
10 
11 #include <ros/node_handle.h>
12 
13 #include <boost/signals2.hpp>
14 #include <boost/circular_buffer.hpp>
15 
16 namespace rosmon
17 {
18 
19 namespace monitor
20 {
21 
26 {
27 public:
28  typedef std::shared_ptr<NodeMonitor> Ptr;
29  typedef std::shared_ptr<NodeMonitor> ConstPtr;
30 
32  enum State
33  {
38  };
39 
48  launch::Node::ConstPtr launchNode,
49  FDWatcher::Ptr fdWatcher, ros::NodeHandle& nh);
50  ~NodeMonitor();
51 
53 
54 
56  void start();
57 
59  void stop(bool restart = false);
60 
62  void restart();
63 
69  void shutdown();
70 
76  void forceExit();
77 
79  bool running() const;
80 
82  State state() const;
84 
86 
87 
89  inline bool coredumpAvailable() const
90  { return !m_debuggerCommand.empty(); }
91 
97  inline std::string debuggerCommand() const
98  { return m_debuggerCommand; }
99 
109  void launchDebugger();
111 
113 
114 
115  void beginStatUpdate();
116  void addCPUTime(uint64_t userTime, uint64_t systemTime);
117  void addMemory(uint64_t memoryBytes);
118  void endStatUpdate(double elapsedTimeInTicks);
119 
126  inline double userLoad() const
127  { return m_userLoad; }
128 
135  inline double systemLoad() const
136  { return m_systemLoad; }
137 
146  inline uint64_t memory() const
147  { return m_memory; }
148 
149  inline unsigned int restartCount() const
150  { return m_restartCount; }
151 
152  inline uint64_t memoryLimit() const
153  { return m_launchNode->memoryLimitByte();}
154 
155  inline double cpuLimit() const
156  { return m_launchNode->cpuLimit();}
157 
159 
161  inline std::string name() const
162  { return m_launchNode->name(); }
163 
165  inline std::string namespaceString() const
166  { return m_launchNode->namespaceString(); }
167 
169  inline std::string fullName() const
170  {
171  return namespaceString() + "/" + name();
172  }
173 
175  inline int pid() const
176  { return m_pid; }
177 
179  inline double stopTimeout() const
180  { return m_launchNode->stopTimeout(); }
181 
182  void setMuted(bool muted);
183 
184  bool isMuted() const
185  { return m_muted; }
186 
192  boost::signals2::signal<void(LogEvent)> logMessageSignal;
193 
195  boost::signals2::signal<void(std::string)> exitedSignal;
196 private:
197  enum Command
198  {
202  };
203 
204  std::vector<std::string> composeCommand() const;
205 
206  void communicate();
207  void communicateStderr();
208 
209  template<typename... Args>
210  void log(const char* format, Args&& ... args);
211 
212  template<typename... Args>
213  void logTyped(LogEvent::Type type, const char* format, Args&& ... args);
214 
215  void checkStop();
216  void gatherCoredump(int signal);
217 
219 
221 
222  boost::circular_buffer<char> m_rxBuffer;
223  boost::circular_buffer<char> m_stderrBuffer;
224 
225  int m_pid = -1;
226  int m_fd = -1;
227  int m_stderrFD = -1;
229 
232 
234 
236 
237  std::string m_debuggerCommand;
238 
239  unsigned int m_restartCount = 0;
240 
241  uint64_t m_userTime = 0;
242  uint64_t m_systemTime = 0;
243  double m_userLoad = 0.0;
244  double m_systemLoad = 0.0;
245  uint64_t m_memory = 0;
246 
250 
251  bool m_firstStart = true;
252 
253  bool m_muted = false;
254 };
255 
256 }
257 
258 }
259 
260 #endif
uint64_t memory() const
Total system memory used by the node.
Definition: node_monitor.h:146
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:195
void start()
Start the node.
void forceExit()
Finish shutdown sequence.
double stopTimeout() const
Node stop timeout.
Definition: node_monitor.h:179
double userLoad() const
Estimate of the userspace load.
Definition: node_monitor.h:126
Monitors a single node process.
Definition: node_monitor.h:25
void addMemory(uint64_t memoryBytes)
void stop(bool restart=false)
Stop the node.
boost::circular_buffer< char > m_rxBuffer
Definition: node_monitor.h:222
std::shared_ptr< NodeMonitor > ConstPtr
Definition: node_monitor.h:29
boost::circular_buffer< char > m_stderrBuffer
Definition: node_monitor.h:223
unsigned int restartCount() const
Definition: node_monitor.h:149
double systemLoad() const
Estimate of the kernelspace load.
Definition: node_monitor.h:135
std::string m_processWorkingDirectory
Definition: node_monitor.h:247
bool coredumpAvailable() const
Is a core dump available from a crash under rosmon control?
Definition: node_monitor.h:89
void log(const char *format, Args &&...args)
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:34
std::string namespaceString() const
Node namespace.
Definition: node_monitor.h:165
void gatherCoredump(int signal)
void launchDebugger()
Launch gdb interactively.
Waiting for automatic restart after crash.
Definition: node_monitor.h:37
boost::signals2::signal< void(LogEvent)> logMessageSignal
Logging signal.
Definition: node_monitor.h:192
int pid() const
Node PID.
Definition: node_monitor.h:175
uint64_t memoryLimit() const
Definition: node_monitor.h:152
std::string debuggerCommand() const
What command should we use to debug the coredump?
Definition: node_monitor.h:97
ros::WallTimer m_stopCheckTimer
Definition: node_monitor.h:230
void endStatUpdate(double elapsedTimeInTicks)
std::string fullName() const
Full name including namespace.
Definition: node_monitor.h:169
void shutdown()
Start shutdown sequence.
bool running() const
Is the node running?
std::vector< std::string > composeCommand() const
launch::Node::ConstPtr m_launchNode
Definition: node_monitor.h:218
Crashed (i.e. exited with code != 0)
Definition: node_monitor.h:36
State state() const
Get process state.
void logTyped(LogEvent::Type type, const char *format, Args &&...args)
void restart()
Restart the node.
std::string name() const
Node name.
Definition: node_monitor.h:161
std::shared_ptr< NodeMonitor > Ptr
Definition: node_monitor.h:28


rosmon_core
Author(s): Max Schwarz
autogenerated on Sat Jan 9 2021 03:35:43