6 #include <rosmon_msgs/State.h> 14 const std::string& diagnosticsPrefix)
17 , m_diagnosticsEnabled(enableDiagnostics)
31 rosmon_msgs::State
state;
39 rosmon_msgs::NodeState nstate;
40 nstate.name = node->name();
41 nstate.ns = node->namespaceString();
46 nstate.state = nstate.RUNNING;
49 nstate.state = nstate.CRASHED;
52 nstate.state = nstate.IDLE;
55 nstate.state = nstate.WAITING;
58 nstate.state = nstate.IDLE;
62 nstate.restart_count = node->restartCount();
64 nstate.user_load =
static_cast<float>(node->userLoad());
65 nstate.system_load =
static_cast<float>(node->systemLoad());
67 nstate.memory = node->memory();
69 state.nodes.push_back(nstate);
77 auto it = std::find_if(
87 case rosmon_msgs::StartStopRequest::START:
90 case rosmon_msgs::StartStopRequest::STOP:
93 case rosmon_msgs::StartStopRequest::RESTART:
106 rosmon_msgs::State
state;
const std::vector< NodeMonitor::Ptr > & nodes() const
void publish(const boost::shared_ptr< M > &message) const
std::shared_ptr< NodeMonitor > ConstPtr
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::unique_ptr< DiagnosticsPublisher > m_diagnosticsPublisher
ros::ServiceServer m_srv_startStop
Idle (e.g. exited with code 0)
ROSInterface(monitor::Monitor *monitor, bool enableDiagnostics=false, const std::string &diagnosticsPrefix={})
Waiting for automatic restart after crash.
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
monitor::Monitor * m_monitor
bool handleStartStop(rosmon_msgs::StartStopRequest &req, rosmon_msgs::StartStopResponse &resp)
Crashed (i.e. exited with code != 0)
ros::WallTimer m_updateTimer
ros::Publisher m_pub_state
bool m_diagnosticsEnabled