diff --git a/rosboard/handlers.py b/rosboard/handlers.py index c5d21373..24178ee6 100644 --- a/rosboard/handlers.py +++ b/rosboard/handlers.py @@ -5,6 +5,7 @@ import tornado.web import tornado.websocket import traceback +import types import uuid from . import __version__ @@ -16,6 +17,7 @@ def set_extra_headers(self, path): class ROSBoardSocketHandler(tornado.websocket.WebSocketHandler): sockets = set() + def initialize(self, node): # store the instance of the ROS node that created this WebSocketHandler so we can access it later self.node = node @@ -32,6 +34,13 @@ def open(self): self.set_nodelay(True) + # polyfill of is_closing() method for older versions of tornado + if not hasattr(self.ws_connection, "is_closing"): + self.ws_connection.is_closing = types.MethodType( + lambda self_: self_.stream.closed() or self_.client_terminated or self_.server_terminated, + self.ws_connection + ) + self.update_intervals_by_topic = {} # this socket's throttle rate on each topic self.last_data_times_by_topic = {} # last time this socket received data on each topic diff --git a/rosboard/html/js/index.js b/rosboard/html/js/index.js index 2ac3185b..c945f3ea 100644 --- a/rosboard/html/js/index.js +++ b/rosboard/html/js/index.js @@ -138,7 +138,13 @@ let onTopics = function(topics) { $('') .addClass("mdl-navigation__link") .click(() => { initSubscribe({topicName: "_top", topicType: "rosboard_msgs/msg/ProcessList"}); }) - .text("top") + .text("Processes") + .appendTo($("#topics-nav-system")); + + $('') + .addClass("mdl-navigation__link") + .click(() => { initSubscribe({topicName: "_system_stats", topicType: "rosboard_msgs/msg/SystemStats"}); }) + .text("System stats") .appendTo($("#topics-nav-system")); } diff --git a/rosboard/html/js/viewers/GeometryViewer.js b/rosboard/html/js/viewers/GeometryViewer.js index 9e23c541..835cc6a0 100644 --- a/rosboard/html/js/viewers/GeometryViewer.js +++ b/rosboard/html/js/viewers/GeometryViewer.js @@ -1,6 +1,6 @@ "use strict"; -class OdometryViewer extends Space2DViewer { +class GeometryViewer extends Space2DViewer { _quatToEuler(q) { let euler = {}; @@ -132,9 +132,9 @@ class OdometryViewer extends Space2DViewer { } } -OdometryViewer.friendlyName = "2D view"; +GeometryViewer.friendlyName = "2D view"; -OdometryViewer.supportedTypes = [ +GeometryViewer.supportedTypes = [ "geometry_msgs/msg/Pose", "geometry_msgs/msg/PoseStamped", "geometry_msgs/msg/PoseWithCovariance", @@ -145,6 +145,6 @@ OdometryViewer.supportedTypes = [ "nav_msgs/msg/Odometry", ]; -OdometryViewer.maxUpdateRate = 10.0; +GeometryViewer.maxUpdateRate = 10.0; -Viewer.registerViewer(OdometryViewer); +Viewer.registerViewer(GeometryViewer); diff --git a/rosboard/rosboard.py b/rosboard/rosboard.py index 34dc3b94..a3e30fed 100755 --- a/rosboard/rosboard.py +++ b/rosboard/rosboard.py @@ -21,6 +21,7 @@ from rosboard.serialization import ros2dict from rosboard.subscribers.dmesg_subscriber import DMesgSubscriber from rosboard.subscribers.processes_subscriber import ProcessesSubscriber +from rosboard.subscribers.system_stats_subscriber import SystemStatsSubscriber from rosboard.subscribers.dummy_subscriber import DummySubscriber from rosboard.handlers import ROSBoardSocketHandler, NoCacheStaticFileHandler @@ -181,6 +182,12 @@ def sync_subs(self): self.local_subs[topic_name] = DMesgSubscriber(self.on_dmesg) continue + if topic_name == "_system_stats": + if topic_name not in self.local_subs: + rospy.loginfo("Subscribing to _system_stats [non-ros]") + self.local_subs[topic_name] = SystemStatsSubscriber(self.on_system_stats) + continue + if topic_name == "_top": if topic_name not in self.local_subs: rospy.loginfo("Subscribing to _top [non-ros]") @@ -240,6 +247,29 @@ def sync_subs(self): self.lock.release() + def on_system_stats(self, system_stats): + """ + system stats received. send it off to the client as a "fake" ROS message (which could at some point be a real ROS message) + """ + if self.event_loop is None: + return + + msg_dict = { + "_topic_name": "_system_stats", # special non-ros topics start with _ + "_topic_type": "rosboard_msgs/msg/SystemStats", + } + + for key, value in system_stats.items(): + msg_dict[key] = value + + self.event_loop.add_callback( + ROSBoardSocketHandler.broadcast, + [ + ROSBoardSocketHandler.MSG_MSG, + msg_dict + ] + ) + def on_top(self, processes): """ processes list received. send it off to the client as a "fake" ROS message (which could at some point be a real ROS message) diff --git a/rosboard/subscribers/system_stats_subscriber.py b/rosboard/subscribers/system_stats_subscriber.py index 906e00e3..5ba61125 100644 --- a/rosboard/subscribers/system_stats_subscriber.py +++ b/rosboard/subscribers/system_stats_subscriber.py @@ -1,50 +1,69 @@ #!/usr/bin/env python3 -import psutil -import select -import subprocess +try: + import psutil +except (ImportError, ModuleNotFoundError) as e: + psutil = None + import time import threading import traceback +def mean(list): + return sum(list)/len(list) + class SystemStatsSubscriber(object): def __init__(self, callback): self.callback = callback - self.process = None + self.stop = False threading.Thread(target = self.start, daemon = True).start() def __del__(self): - if self.process: - self.process.terminate() - self.process = None + self.stop = True + pass def unregister(self): - if self.process: - self.process.terminate() - self.process = None + self.stop = True + pass def start(self): - try: - self.process = subprocess.Popen(['dmesg', '--follow'], stdout = subprocess.PIPE) - p = select.poll() - p.register(self.process.stdout, select.POLLIN) - - while True: - time.sleep(0.1) - - if self.process is None: - break + if psutil is None: + self.callback({"_error": "Please install psutil (sudo pip3 install --upgrade psutil) to use this feature."}) + return + + while not self.stop: + try: + p = psutil.Process() + + with p.oneshot(): + sensors_temperatures = psutil.sensors_temperatures() + cpu_percent = psutil.cpu_percent(percpu = True) + net_io_counters = psutil.net_io_counters() + virtual_memory = psutil.virtual_memory() + swap_memory = psutil.swap_memory() + disk_usage = psutil.disk_usage('/') + + status = {} + + status["cpu_percent"] = cpu_percent + + if "coretemp" in sensors_temperatures: + status["temp_coretemp"] = mean(list(map( + lambda x:x.current, + sensors_temperatures["coretemp"] + ))) - lines = [] - while p.poll(1): - lines.append(self.process.stdout.readline().decode('utf-8').strip()) + status["net_bytes_sent"] = net_io_counters.bytes_sent + status["net_bytes_recv"] = net_io_counters.bytes_recv + status["disk_usage_percent"] = disk_usage.percent + status["virtual_memory_percent"] = virtual_memory.percent + status["swap_memory_percent"] = swap_memory.percent - text = "\n".join(lines) - if len(text) > 0: - self.callback("\n".join(lines)) - except: - traceback.print_exc() + except Exception as e: + traceback.print_exc() + self.callback(status) + time.sleep(3) if __name__ == "__main__": # Run test