4 #ifndef ROSMON_MONITOR_NODE_MONITOR_H 5 #define ROSMON_MONITOR_NODE_MONITOR_H 7 #include "../launch/node.h" 8 #include "../launch/launch_config.h" 9 #include "../fd_watcher.h" 10 #include "../log_event.h" 15 #include <boost/signals2.hpp> 16 #include <boost/circular_buffer.hpp> 30 typedef std::shared_ptr<NodeMonitor>
Ptr;
119 void addCPUTime(uint64_t userTime, uint64_t systemTime);
167 inline std::string
name()
const 215 template<
typename... Args>
216 void log(
const char* format, Args&& ... args);
218 template<
typename... Args>
void log(const char *format, Args &&... args)
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.
NodeMonitor(const launch::LaunchConfig::ConstPtr &config, const launch::Node::ConstPtr &launchNode, FDWatcher::Ptr fdWatcher, ros::NodeHandle &nh)
Constructor.
Monitors a single node process.
void addMemory(uint64_t memoryBytes)
void stop(bool restart=false)
Stop the node.
std::shared_ptr< NodeMonitor > ConstPtr
unsigned int restartCount() const
std::string m_processWorkingDirectory
uint64_t memoryLimit() const
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)
void gatherCoredump(int signal)
void logTyped(LogEvent::Type type, const char *format, Args &&... args)
void setMuted(bool muted)
unsigned int m_restartCount
void launchDebugger()
Launch gdb interactively.
int numRespawnsAllowed() const
Waiting for automatic restart after crash.
std::pair< int, int > createPTY()
std::string debuggerCommand() const
What command should we use to debug the coredump?
boost::signals2::signal< void(LogEvent)> logMessageSignal
Logging signal.
bool coredumpAvailable() const
Is a core dump available from a crash under rosmon control?
FDWatcher::Ptr m_fdWatcher
std::shared_ptr< const LaunchConfig > ConstPtr
ros::WallTimer m_stopCheckTimer
void endStatUpdate(double elapsedTimeInTicks)
double systemLoad() const
Estimate of the kernelspace load.
std::string fullName() const
Full name including namespace.
launch::LaunchConfig::ConstPtr m_launchConfig
void shutdown()
Start shutdown sequence.
launch::Node::ConstPtr m_launchNode
Crashed (i.e. exited with code != 0)
std::vector< std::string > composeCommand() const
bool m_processWorkingDirectoryCreated
void restart()
Restart the node.
ros::WallTimer m_restartTimer
std::string name() const
Node name.
std::string m_lastWorkingDirectory
double userLoad() const
Estimate of the userspace load.
std::shared_ptr< NodeMonitor > Ptr
double stopTimeout() const
Node stop timeout.
uint64_t memory() const
Total system memory used by the node.
std::string namespaceString() const
Node namespace.