4 #ifndef ROSMON_MONITOR_NODE_MONITOR_H 5 #define ROSMON_MONITOR_NODE_MONITOR_H 7 #include "../launch/node.h" 8 #include "../fd_watcher.h" 9 #include "../log_event.h" 13 #include <boost/signals2.hpp> 14 #include <boost/circular_buffer.hpp> 28 typedef std::shared_ptr<NodeMonitor>
Ptr;
116 void addCPUTime(uint64_t userTime, uint64_t systemTime);
161 inline std::string
name()
const 209 template<
typename... Args>
210 void log(
const char* format, Args&& ... args);
212 template<
typename... Args>
uint64_t memory() const
Total system memory used by the node.
std::shared_ptr< const Node > ConstPtr
std::string m_debuggerCommand
boost::signals2::signal< void(std::string)> exitedSignal
Signalled whenever the process exits.
void start()
Start the node.
void forceExit()
Finish shutdown sequence.
double stopTimeout() const
Node stop timeout.
double userLoad() const
Estimate of the userspace load.
Monitors a single node process.
void addMemory(uint64_t memoryBytes)
void stop(bool restart=false)
Stop the node.
boost::circular_buffer< char > m_rxBuffer
std::shared_ptr< NodeMonitor > ConstPtr
boost::circular_buffer< char > m_stderrBuffer
unsigned int restartCount() const
double systemLoad() const
Estimate of the kernelspace load.
std::string m_processWorkingDirectory
bool coredumpAvailable() const
Is a core dump available from a crash under rosmon control?
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)
std::string namespaceString() const
Node namespace.
void gatherCoredump(int signal)
void setMuted(bool muted)
unsigned int m_restartCount
void launchDebugger()
Launch gdb interactively.
Waiting for automatic restart after crash.
boost::signals2::signal< void(LogEvent)> logMessageSignal
Logging signal.
FDWatcher::Ptr m_fdWatcher
int pid() const
Node PID.
uint64_t memoryLimit() const
std::string debuggerCommand() const
What command should we use to debug the coredump?
ros::WallTimer m_stopCheckTimer
void endStatUpdate(double elapsedTimeInTicks)
std::string fullName() const
Full name including namespace.
void shutdown()
Start shutdown sequence.
bool running() const
Is the node running?
std::vector< std::string > composeCommand() const
launch::Node::ConstPtr m_launchNode
Crashed (i.e. exited with code != 0)
State state() const
Get process state.
bool m_processWorkingDirectoryCreated
void logTyped(LogEvent::Type type, const char *format, Args &&...args)
void restart()
Restart the node.
std::string name() const
Node name.
ros::WallTimer m_restartTimer
std::string m_lastWorkingDirectory
std::shared_ptr< NodeMonitor > Ptr