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 "../launch/launch_config.h"
9 #include "../fd_watcher.h"
10 #include "../log_event.h"
11 #include "log_parser.h"
12 
13 #include <ros/node_handle.h>
14 
15 #include <boost/signals2.hpp>
16 #include <boost/circular_buffer.hpp>
17 
18 namespace rosmon
19 {
20 
21 namespace monitor
22 {
23 
28 {
29 public:
30  typedef std::shared_ptr<NodeMonitor> Ptr;
31  typedef std::shared_ptr<NodeMonitor> ConstPtr;
32 
34  enum State
35  {
40  };
41 
50  const launch::LaunchConfig::ConstPtr& config,
51  const launch::Node::ConstPtr& launchNode,
52  FDWatcher::Ptr fdWatcher, ros::NodeHandle& nh);
53  ~NodeMonitor();
54 
56 
57 
59  void start();
60 
62  void stop(bool restart = false);
63 
65  void restart();
66 
72  void shutdown();
73 
79  void forceExit();
80 
82  bool running() const;
83 
85  State state() const;
87 
89 
90 
92  inline bool coredumpAvailable() const
93  { return !m_debuggerCommand.empty(); }
94 
100  inline std::string debuggerCommand() const
101  { return m_debuggerCommand; }
102 
112  void launchDebugger();
114 
116 
117 
118  void beginStatUpdate();
119  void addCPUTime(uint64_t userTime, uint64_t systemTime);
120  void addMemory(uint64_t memoryBytes);
121  void endStatUpdate(double elapsedTimeInTicks);
122 
129  inline double userLoad() const
130  { return m_userLoad; }
131 
138  inline double systemLoad() const
139  { return m_systemLoad; }
140 
149  inline uint64_t memory() const
150  { return m_memory; }
151 
152  inline unsigned int restartCount() const
153  { return m_restartCount; }
154 
155  inline int numRespawnsAllowed() const
156  { return m_launchNode->numRespawnsAllowed(); }
157 
158  inline uint64_t memoryLimit() const
159  { return m_launchNode->memoryLimitByte();}
160 
161  inline double cpuLimit() const
162  { return m_launchNode->cpuLimit();}
163 
165 
167  inline std::string name() const
168  { return m_launchNode->name(); }
169 
171  inline std::string namespaceString() const
172  { return m_launchNode->namespaceString(); }
173 
175  inline std::string fullName() const
176  {
177  return namespaceString() + "/" + name();
178  }
179 
181  inline int pid() const
182  { return m_pid; }
183 
185  inline double stopTimeout() const
186  { return m_launchNode->stopTimeout(); }
187 
188  void setMuted(bool muted);
189 
190  bool isMuted() const
191  { return m_muted; }
192 
198  boost::signals2::signal<void(LogEvent)> logMessageSignal;
199 
201  boost::signals2::signal<void(std::string)> exitedSignal;
202 private:
203  enum Command
204  {
208  };
209 
210  std::vector<std::string> composeCommand() const;
211 
212  void communicate();
213  void communicateStderr();
214 
215  template<typename... Args>
216  void log(const char* format, Args&& ... args);
217 
218  template<typename... Args>
219  void logTyped(LogEvent::Type type, const char* format, Args&& ... args);
220 
221  void checkStop();
222  void gatherCoredump(int signal);
223 
224  std::pair<int,int> createPTY();
225 
228 
230 
233 
234  int m_pid = -1;
235  int m_fd = -1;
236  int m_stderrFD = -1;
238 
241 
243 
245 
246  std::string m_debuggerCommand;
247 
248  unsigned int m_restartCount = 0;
249 
250  uint64_t m_userTime = 0;
251  uint64_t m_systemTime = 0;
252  double m_userLoad = 0.0;
253  double m_systemLoad = 0.0;
254  uint64_t m_memory = 0;
255 
259 
260  bool m_firstStart = true;
261 
262  bool m_muted = false;
263 };
264 
265 }
266 
267 }
268 
269 #endif
void log(const char *format, Args &&... args)
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:201
void start()
Start the node.
void forceExit()
Finish shutdown sequence.
NodeMonitor(const launch::LaunchConfig::ConstPtr &config, const launch::Node::ConstPtr &launchNode, FDWatcher::Ptr fdWatcher, ros::NodeHandle &nh)
Constructor.
Monitors a single node process.
Definition: node_monitor.h:27
void addMemory(uint64_t memoryBytes)
void stop(bool restart=false)
Stop the node.
std::shared_ptr< NodeMonitor > ConstPtr
Definition: node_monitor.h:31
unsigned int restartCount() const
Definition: node_monitor.h:152
std::string m_processWorkingDirectory
Definition: node_monitor.h:256
uint64_t memoryLimit() const
Definition: node_monitor.h:158
void addCPUTime(uint64_t userTime, uint64_t systemTime)
State state() const
Get process state.
bool running() const
Is the node running?
Idle (e.g. exited with code 0)
Definition: node_monitor.h:36
void gatherCoredump(int signal)
void logTyped(LogEvent::Type type, const char *format, Args &&... args)
void launchDebugger()
Launch gdb interactively.
Waiting for automatic restart after crash.
Definition: node_monitor.h:39
std::pair< int, int > createPTY()
std::string debuggerCommand() const
What command should we use to debug the coredump?
Definition: node_monitor.h:100
boost::signals2::signal< void(LogEvent)> logMessageSignal
Logging signal.
Definition: node_monitor.h:198
bool coredumpAvailable() const
Is a core dump available from a crash under rosmon control?
Definition: node_monitor.h:92
std::shared_ptr< const LaunchConfig > ConstPtr
ros::WallTimer m_stopCheckTimer
Definition: node_monitor.h:239
void endStatUpdate(double elapsedTimeInTicks)
double systemLoad() const
Estimate of the kernelspace load.
Definition: node_monitor.h:138
std::string fullName() const
Full name including namespace.
Definition: node_monitor.h:175
launch::LaunchConfig::ConstPtr m_launchConfig
Definition: node_monitor.h:226
void shutdown()
Start shutdown sequence.
int pid() const
Node PID.
Definition: node_monitor.h:181
launch::Node::ConstPtr m_launchNode
Definition: node_monitor.h:227
Crashed (i.e. exited with code != 0)
Definition: node_monitor.h:38
std::vector< std::string > composeCommand() const
void restart()
Restart the node.
std::string name() const
Node name.
Definition: node_monitor.h:167
double userLoad() const
Estimate of the userspace load.
Definition: node_monitor.h:129
std::shared_ptr< NodeMonitor > Ptr
Definition: node_monitor.h:30
double stopTimeout() const
Node stop timeout.
Definition: node_monitor.h:185
uint64_t memory() const
Total system memory used by the node.
Definition: node_monitor.h:149
std::string namespaceString() const
Node namespace.
Definition: node_monitor.h:171


rosmon_core
Author(s): Max Schwarz
autogenerated on Fri Jun 16 2023 02:15:06