├── resource
└── rosboard
├── .gitignore
├── rosboard
├── subscribers
│ ├── __init__.py
│ ├── dummy_subscriber.py
│ ├── dmesg_subscriber.py
│ ├── processes_subscriber.py
│ └── system_stats_subscriber.py
├── __init__.py
├── rospy2
│ ├── constants.py
│ └── __init__.pyc
├── html
│ ├── js
│ │ ├── transports
│ │ │ ├── Rosbag2Transport.js
│ │ │ ├── RosBridgeTransport.js
│ │ │ ├── DeviceSensorTransport.js
│ │ │ ├── RosbagTransport.js
│ │ │ └── WebSocketV1Transport.js
│ │ ├── import-helper.js
│ │ ├── viewers
│ │ │ ├── PolygonViewer.js
│ │ │ ├── MapViewer.js
│ │ │ ├── ImageViewer.js
│ │ │ ├── ProcessListViewer.js
│ │ │ ├── GenericViewer.js
│ │ │ ├── LogViewer.js
│ │ │ ├── TimeSeriesPlotViewer.js
│ │ │ ├── LaserScanViewer.js
│ │ │ ├── DiagnosticViewer.js
│ │ │ ├── GeometryViewer.js
│ │ │ ├── PointCloud2Viewer.js
│ │ │ └── meta
│ │ │ │ ├── Space3DViewer.js
│ │ │ │ ├── Viewer.js
│ │ │ │ └── Space2DViewer.js
│ │ ├── eventemitter2.min.js
│ │ ├── jquery.transit.min.js
│ │ ├── index.js
│ │ ├── leaflet.easy-button.js
│ │ └── draggabilly.pkgd.min.js
│ ├── css
│ │ ├── images
│ │ │ ├── layers.png
│ │ │ ├── layers-2x.png
│ │ │ ├── marker-icon.png
│ │ │ ├── marker-shadow.png
│ │ │ └── marker-icon-2x.png
│ │ ├── material-icons.css
│ │ ├── leaflet.easy-button.css
│ │ ├── uPlot.min.css
│ │ └── index.css
│ ├── fonts
│ │ ├── MaterialIcons-Regular.eot
│ │ ├── MaterialIcons-Regular.ttf
│ │ ├── MaterialIcons-Regular.woff
│ │ ├── MaterialIcons-Regular.woff2
│ │ ├── jetbrains-mono-v6-latin-300.eot
│ │ ├── jetbrains-mono-v6-latin-300.ttf
│ │ ├── jetbrains-mono-v6-latin-300.woff
│ │ ├── jetbrains-mono-v6-latin-700.eot
│ │ ├── jetbrains-mono-v6-latin-700.ttf
│ │ ├── jetbrains-mono-v6-latin-700.woff
│ │ ├── titillium-web-v10-latin-300.eot
│ │ ├── titillium-web-v10-latin-300.ttf
│ │ ├── titillium-web-v10-latin-300.woff
│ │ ├── titillium-web-v10-latin-700.eot
│ │ ├── titillium-web-v10-latin-700.ttf
│ │ ├── titillium-web-v10-latin-700.woff
│ │ ├── jetbrains-mono-v6-latin-300.woff2
│ │ ├── jetbrains-mono-v6-latin-700.woff2
│ │ ├── titillium-web-v10-latin-300.woff2
│ │ └── titillium-web-v10-latin-700.woff2
│ └── index.html
├── message_serialization.py
├── serialization.py
├── cv_bridge.py
├── handlers.py
└── compression.py
├── requirements.txt
├── nodes
└── rosboard_node
├── screenshots
├── screenshot1.jpg
├── screenshot2.jpg
├── screenshot3.jpg
├── screenshot4.jpg
└── screenshot5.jpg
├── setup.cfg
├── run
├── launch
└── rosboard.launch
├── CMakeLists.txt
├── package.xml
├── setup.py
├── CHANGELOG.txt
├── LICENSE
└── README.md
/resource/rosboard:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | __pycache__
2 |
--------------------------------------------------------------------------------
/rosboard/subscribers/__init__.py:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/requirements.txt:
--------------------------------------------------------------------------------
1 | tornado
2 | simplejpeg
3 |
--------------------------------------------------------------------------------
/rosboard/__init__.py:
--------------------------------------------------------------------------------
1 | __version__ = "1.3.1"
2 |
--------------------------------------------------------------------------------
/rosboard/rospy2/constants.py:
--------------------------------------------------------------------------------
1 | DEBUG = 1
2 | INFO = 2
3 | WARN = 4
4 | ERROR = 8
5 | FATAL = 16
6 |
--------------------------------------------------------------------------------
/nodes/rosboard_node:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | from rosboard.rosboard import main
4 | main()
5 |
6 |
--------------------------------------------------------------------------------
/rosboard/html/js/transports/Rosbag2Transport.js:
--------------------------------------------------------------------------------
1 | class Rosbag2Transport {
2 | // not yet implemented
3 | }
--------------------------------------------------------------------------------
/screenshots/screenshot1.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/screenshots/screenshot1.jpg
--------------------------------------------------------------------------------
/screenshots/screenshot2.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/screenshots/screenshot2.jpg
--------------------------------------------------------------------------------
/screenshots/screenshot3.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/screenshots/screenshot3.jpg
--------------------------------------------------------------------------------
/screenshots/screenshot4.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/screenshots/screenshot4.jpg
--------------------------------------------------------------------------------
/screenshots/screenshot5.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/screenshots/screenshot5.jpg
--------------------------------------------------------------------------------
/rosboard/html/js/transports/RosBridgeTransport.js:
--------------------------------------------------------------------------------
1 | class RosBridgeTransport {
2 | // not implemented yet
3 | }
--------------------------------------------------------------------------------
/rosboard/rospy2/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/rospy2/__init__.pyc
--------------------------------------------------------------------------------
/setup.cfg:
--------------------------------------------------------------------------------
1 | [develop]
2 | script_dir=$base/lib/rosboard
3 | [install]
4 | install_scripts=$base/lib/rosboard
5 |
--------------------------------------------------------------------------------
/rosboard/html/js/transports/DeviceSensorTransport.js:
--------------------------------------------------------------------------------
1 | class DeviceSensorTransport {
2 | // not implemented yet
3 | }
--------------------------------------------------------------------------------
/rosboard/html/js/transports/RosbagTransport.js:
--------------------------------------------------------------------------------
1 | class RosbagTransport {
2 | // not yet implemented
3 | }
4 |
--------------------------------------------------------------------------------
/rosboard/html/css/images/layers.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/css/images/layers.png
--------------------------------------------------------------------------------
/rosboard/html/css/images/layers-2x.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/css/images/layers-2x.png
--------------------------------------------------------------------------------
/rosboard/html/css/images/marker-icon.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/css/images/marker-icon.png
--------------------------------------------------------------------------------
/rosboard/html/css/images/marker-shadow.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/css/images/marker-shadow.png
--------------------------------------------------------------------------------
/rosboard/html/css/images/marker-icon-2x.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/css/images/marker-icon-2x.png
--------------------------------------------------------------------------------
/rosboard/html/fonts/MaterialIcons-Regular.eot:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/MaterialIcons-Regular.eot
--------------------------------------------------------------------------------
/rosboard/html/fonts/MaterialIcons-Regular.ttf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/MaterialIcons-Regular.ttf
--------------------------------------------------------------------------------
/rosboard/html/fonts/MaterialIcons-Regular.woff:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/MaterialIcons-Regular.woff
--------------------------------------------------------------------------------
/rosboard/html/fonts/MaterialIcons-Regular.woff2:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/MaterialIcons-Regular.woff2
--------------------------------------------------------------------------------
/run:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | import rosboard.rosboard
4 | print("Running from %s" % str(rosboard.__path__))
5 | rosboard.rosboard.main()
6 |
7 |
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-300.eot:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-300.eot
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-300.ttf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-300.ttf
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-300.woff:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-300.woff
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-700.eot:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-700.eot
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-700.ttf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-700.ttf
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-700.woff:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-700.woff
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-300.eot:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-300.eot
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-300.ttf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-300.ttf
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-300.woff:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-300.woff
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-700.eot:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-700.eot
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-700.ttf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-700.ttf
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-700.woff:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-700.woff
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-300.woff2:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-300.woff2
--------------------------------------------------------------------------------
/rosboard/html/fonts/jetbrains-mono-v6-latin-700.woff2:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/jetbrains-mono-v6-latin-700.woff2
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-300.woff2:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-300.woff2
--------------------------------------------------------------------------------
/rosboard/html/fonts/titillium-web-v10-latin-700.woff2:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nguyen-v/rosboard/HEAD/rosboard/html/fonts/titillium-web-v10-latin-700.woff2
--------------------------------------------------------------------------------
/rosboard/subscribers/dummy_subscriber.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | class DummySubscriber(object):
4 | def __init__(self):
5 | pass
6 |
7 | def __del__(self):
8 | pass
9 |
10 | def unregister(self):
11 | pass
12 |
13 |
--------------------------------------------------------------------------------
/launch/rosboard.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(rosboard)
3 |
4 | find_package(catkin REQUIRED COMPONENTS
5 | rospy
6 | std_msgs
7 | sensor_msgs
8 | )
9 |
10 | catkin_python_setup()
11 | catkin_package()
12 |
13 | catkin_install_python(PROGRAMS
14 | nodes/rosboard_node
15 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
16 | )
17 |
18 | install(DIRECTORY
19 | launch
20 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
21 | )
22 |
--------------------------------------------------------------------------------
/rosboard/html/js/import-helper.js:
--------------------------------------------------------------------------------
1 | let importedPaths = {};
2 |
3 | function importCssOnce(path) {
4 | if(path in importedPaths) return;
5 | $('').appendTo('head').attr({
6 | type: 'text/css',
7 | rel: 'stylesheet',
8 | href: path
9 | });
10 | importedPaths[path] = 1;
11 | }
12 |
13 | function importJsOnce(path) {
14 | if(path in importedPaths) return;
15 | var result = $.ajax({ url: path, dataType: "script", async: false })
16 | if(result.status === 200) {
17 | importedPaths[path] = 1;
18 | } else {
19 | console.log(result.status + " error while importing " + path);
20 | }
21 | }
22 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | rosboard
5 | 1.3.1
6 | ROSBoard
7 | dheera
8 | BSD
9 |
10 | catkin
11 |
12 | python3-tornado
13 | python3-pil
14 |
15 |
16 | catkin
17 | ament_python
18 |
19 |
20 |
--------------------------------------------------------------------------------
/rosboard/html/css/material-icons.css:
--------------------------------------------------------------------------------
1 | @font-face {
2 | font-family: 'Material Icons';
3 | font-style: normal;
4 | font-weight: 400;
5 | src: url(/fonts/MaterialIcons-Regular.eot); /* For IE6-8 */
6 | src: local('Material Icons'),
7 | local('MaterialIcons-Regular'),
8 | url(/fonts/MaterialIcons-Regular.woff2) format('woff2'),
9 | url(/fonts/MaterialIcons-Regular.woff) format('woff'),
10 | url(/fonts/MaterialIcons-Regular.ttf) format('truetype');
11 | }
12 |
13 | .material-icons {
14 | font-family: 'Material Icons';
15 | font-weight: normal;
16 | font-style: normal;
17 | font-size: 24px;
18 | line-height: 1;
19 | letter-spacing: normal;
20 | text-transform: none;
21 | display: inline-block;
22 | white-space: nowrap;
23 | word-wrap: normal;
24 | direction: ltr;
25 | -webkit-font-feature-settings: 'liga';
26 | -webkit-font-smoothing: antialiased;
27 | }
28 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/PolygonViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | class PolygonViewer extends Space2DViewer {
4 | onData(msg) {
5 | this.card.title.text(msg._topic_name);
6 |
7 | let polygon = msg;
8 | if(msg._topic_type.endsWith("Stamped")) {
9 | polygon = msg.polygon;
10 | }
11 |
12 | let points = new Float32Array((polygon.points.length + 1) * 2);
13 |
14 | for(let i = 0; i < polygon.points.length; i++) {
15 | points[2*i] = polygon.points[i].x;
16 | points[2*i+1] = polygon.points[i].y;
17 | }
18 | points[2*polygon.points.length] = polygon.points[0].x;
19 | points[2*polygon.points.length+1] = polygon.points[0].y;
20 | this.draw([
21 | {type: "path", data: [0, 0, 0, 1], color: "#00f060", lineWidth: 2},
22 | {type: "path", data: [0, 0, 1, 0], color: "#f06060", lineWidth: 2},
23 | {type: "path", data: points, color: "#e0e0e0"},
24 | ]);
25 | }
26 | }
27 |
28 | PolygonViewer.friendlyName = "Polygon";
29 |
30 | PolygonViewer.supportedTypes = [
31 | "geometry_msgs/msg/Polygon",
32 | "geometry_msgs/msg/PolygonStamped",
33 | ];
34 |
35 | PolygonViewer.maxUpdateRate = 10.0;
36 |
37 | Viewer.registerViewer(PolygonViewer);
38 |
--------------------------------------------------------------------------------
/rosboard/html/css/leaflet.easy-button.css:
--------------------------------------------------------------------------------
1 | .leaflet-bar button,
2 | .leaflet-bar button:hover {
3 | background-color: #fff;
4 | border: none;
5 | border-bottom: 1px solid #ccc;
6 | width: 26px;
7 | height: 26px;
8 | line-height: 26px;
9 | display: block;
10 | text-align: center;
11 | text-decoration: none;
12 | color: black;
13 | }
14 |
15 | .leaflet-bar button {
16 | background-position: 50% 50%;
17 | background-repeat: no-repeat;
18 | overflow: hidden;
19 | display: block;
20 | }
21 |
22 | .leaflet-bar button:hover {
23 | background-color: #f4f4f4;
24 | }
25 |
26 | .leaflet-bar button:first-of-type {
27 | border-top-left-radius: 4px;
28 | border-top-right-radius: 4px;
29 | }
30 |
31 | .leaflet-bar button:last-of-type {
32 | border-bottom-left-radius: 4px;
33 | border-bottom-right-radius: 4px;
34 | border-bottom: none;
35 | }
36 |
37 | .leaflet-bar.disabled,
38 | .leaflet-bar button.disabled {
39 | cursor: default;
40 | pointer-events: none;
41 | opacity: .4;
42 | }
43 |
44 | .easy-button-button .button-state{
45 | display: block;
46 | width: 100%;
47 | height: 100%;
48 | position: relative;
49 | }
50 |
51 |
52 | .leaflet-touch .leaflet-bar button {
53 | width: 30px;
54 | height: 30px;
55 | line-height: 30px;
56 | }
57 |
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | from setuptools import setup, find_packages
2 |
3 | package_name = 'rosboard'
4 |
5 | setup(
6 | name=package_name,
7 | version='1.3.1',
8 | packages=find_packages(), #[package_name],
9 | data_files=[
10 | ('share/' + package_name, ['package.xml']),
11 | ('share/ament_index/resource_index/packages',
12 | ['resource/' + package_name]),
13 | ],
14 | install_requires=[
15 | 'setuptools',
16 | 'tornado>=4.2.1',
17 | ],
18 | extras_require = {
19 | 'system_stats': ['psutil'],
20 | },
21 | package_data={
22 | 'rosboard': [
23 | 'html/*',
24 | 'html/fonts/*',
25 | 'html/css/*',
26 | 'html/css/images/*',
27 | 'html/js/*',
28 | 'html/js/viewers/*',
29 | 'html/js/viewers/meta/*',
30 | 'html/js/transports/*'
31 | ]
32 | },
33 | #zip_safe=True,
34 | maintainer='dheera',
35 | maintainer_email='dheeradheera.net',
36 | description='ROS node that turns your robot into a web server to visualize ROS topics',
37 | license='BSD',
38 | tests_require=['pytest'],
39 | entry_points={
40 | 'console_scripts': [
41 | "rosboard_node = rosboard.rosboard:main",
42 | ],
43 | },
44 | )
45 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/MapViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | class MapViewer extends Viewer {
4 | /**
5 | * Gets called when Viewer is first initialized.
6 | * @override
7 | **/
8 | onCreate() {
9 | this.viewer = $('
')
10 | .css({'font-size': '11pt'
11 | , "filter": "invert(100%) saturate(50%)"})
12 | .appendTo(this.card.content);
13 |
14 | this.mapId = "map-" + Math.floor(Math.random()*10000);
15 |
16 | this.map = $('')
17 | .css({
18 | "height": "250px",
19 | })
20 | .appendTo(this.viewer);
21 |
22 | this.mapLeaflet = L.map(this.mapId).setView([51.505,-0.09], 15);
23 |
24 | this.mapLeaflet.dragging.disable();
25 |
26 | L.tileLayer('https://{s}.tile.openstreetmap.org/{z}/{x}/{y}.png', {
27 | attribution: '© OpenStreetMap contributors'
28 | }).addTo(this.mapLeaflet);
29 |
30 | this.marker = null;
31 | }
32 |
33 | onData(msg) {
34 | this.card.title.text(msg._topic_name);
35 | if(this.marker) this.mapLeaflet.removeLayer(this.marker);
36 |
37 | this.marker = L.marker([msg.latitude, msg.longitude]);
38 | this.marker.addTo(this.mapLeaflet);
39 | this.mapLeaflet.setView([msg.latitude, msg.longitude]);
40 | }
41 | }
42 |
43 | MapViewer.friendlyName = "Street Map";
44 |
45 | MapViewer.supportedTypes = [
46 | "sensor_msgs/msg/NavSatFix",
47 | ];
48 |
49 | MapViewer.maxUpdateRate = 10.0;
50 |
51 | Viewer.registerViewer(MapViewer);
--------------------------------------------------------------------------------
/rosboard/subscribers/dmesg_subscriber.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | import select
4 | import subprocess
5 | import time
6 | import threading
7 | import traceback
8 |
9 | class DMesgSubscriber(object):
10 | def __init__(self, callback):
11 | self.callback = callback
12 | self.process = None
13 | threading.Thread(target = self.start, daemon = True).start()
14 |
15 | def __del__(self):
16 | if self.process:
17 | self.process.terminate()
18 | self.process = None
19 |
20 | def unregister(self):
21 | if self.process:
22 | self.process.terminate()
23 | self.process = None
24 |
25 | def start(self):
26 | try:
27 | self.process = subprocess.Popen(['dmesg', '--follow'], stdout = subprocess.PIPE)
28 | p = select.poll()
29 | p.register(self.process.stdout, select.POLLIN)
30 |
31 | while True:
32 | time.sleep(0.1)
33 |
34 | if self.process is None:
35 | break
36 |
37 | lines = []
38 | while p.poll(1):
39 | lines.append(self.process.stdout.readline().decode('utf-8').strip())
40 |
41 | text = "\n".join(lines)
42 | if len(text) > 0:
43 | self.callback("\n".join(lines))
44 | except:
45 | traceback.print_exc()
46 |
47 |
48 | if __name__ == "__main__":
49 | # Run test
50 | DMesgSubscriber(lambda msg: print("Received msg: %s" % msg))
51 | time.sleep(100)
52 |
--------------------------------------------------------------------------------
/rosboard/html/css/uPlot.min.css:
--------------------------------------------------------------------------------
1 | .uplot, .uplot *, .uplot *::before, .uplot *::after {box-sizing: border-box;}.uplot {font-family: system-ui, -apple-system, "Segoe UI", Roboto, "Helvetica Neue", Arial, "Noto Sans", sans-serif, "Apple Color Emoji", "Segoe UI Emoji", "Segoe UI Symbol", "Noto Color Emoji";line-height: 1.5;width: min-content;}.u-title {text-align: center;font-size: 18px;font-weight: bold;}.u-wrap {position: relative;user-select: none;}.u-over, .u-under {position: absolute;}.u-under {overflow: hidden;}.uplot canvas {display: block;position: relative;width: 100%;height: 100%;}.u-legend {font-size: 14px;margin: auto;text-align: center;}.u-inline {display: block;}.u-inline * {display: inline-block;}.u-inline tr {margin-right: 16px;}.u-legend th {font-weight: 600;}.u-legend th > * {vertical-align: middle;display: inline-block;}.u-legend .u-marker {width: 1em;height: 1em;margin-right: 4px;background-clip: content-box !important;}.u-inline.u-live th::after {content: ":";vertical-align: middle;}.u-inline:not(.u-live) .u-value {display: none;}.u-series > * {padding: 4px;}.u-series th {cursor: pointer;}.u-legend .u-off > * {opacity: 0.3;}.u-select {background: rgba(0,0,0,0.07);position: absolute;pointer-events: none;}.u-cursor-x, .u-cursor-y {position: absolute;left: 0;top: 0;pointer-events: none;will-change: transform;z-index: 100;}.u-hz .u-cursor-x, .u-vt .u-cursor-y {height: 100%;border-right: 1px dashed #607D8B;}.u-hz .u-cursor-y, .u-vt .u-cursor-x {width: 100%;border-bottom: 1px dashed #607D8B;}.u-cursor-pt {position: absolute;top: 0;left: 0;border-radius: 50%;pointer-events: none;will-change: transform;z-index: 100;/*this has to be !important since we set inline "background" shorthand */background-clip: content-box !important;}.u-select.u-off, .u-cursor-x.u-off, .u-cursor-y.u-off, .u-cursor-pt.u-off {display: none;}
--------------------------------------------------------------------------------
/CHANGELOG.txt:
--------------------------------------------------------------------------------
1 | 1.3.0
2 | -----
3 | * Fixed issues with "'Unknown QoS history policy, at ./src/qos.cpp:61'"
4 |
5 | 1.2.1
6 | -----
7 | * Fix for bug "Viewer not found" when rosboard is installed to system
8 | (setup.py did not catch all the client-side js files).
9 |
10 | 1.2.0
11 | -----
12 | * Experimental support for PointCloud2 with WebGL, and simple compression of point cloud data
13 | * Binary compression of LaserScan range and intensity data
14 | * Support for Pose, PoseStamped, PoseWithCovariance, PoseWithCovarianceStamped
15 | * Support for Point, Point32, Odometry
16 | * Support for DiagnosticArray with aggregation
17 | * Fixed some connection drop rosout logspam issues
18 | * Panning of LaserScan and other 2D types (use 2 fingers to pan/zoom on mobile to avoid conflict with scrolling)
19 | * Remember last viewed topics and bring them back up when page is reloaded
20 | * Allow switching between multiple supported viewers (e.g. 2D spatial view or raw data)
21 | * Pause button
22 |
23 | 1.1.3
24 | -----
25 | * Display hostname of robot in top bar
26 | * Support for sensor_msgs/LaserScan, geometry_msgs/Polygon
27 | * Support for viewing process list ("top")
28 | * Detect lagging connections and disconnect them
29 | * Base64-encode binary messages
30 | * Display error message when custom ROS msg file is not found, instead of hanging without feedback
31 |
32 | 1.1.2
33 | -----
34 | * Resubscribe bug fix
35 | * Sort tree paths alphabetically
36 | * Fix dismissed cards re-appearing bug
37 | * Support for 16-bit greyscale images
38 | * Corrected display colors for bgr8 images
39 | * OccupancyGrid support
40 | * Fix exceptions being thrown when ROS message contain NaN/Inf/-Inf
41 |
42 | 1.1.1
43 | -----
44 | * Tree view of topics
45 | * Cards appear immediately with spinner instead of waiting for next ROS message before appearing
46 | * Bug fix in ROS node subscriber
47 |
--------------------------------------------------------------------------------
/rosboard/subscribers/processes_subscriber.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | import re
4 | import select
5 | import subprocess
6 | import time
7 | import threading
8 | import traceback
9 |
10 | class ProcessesSubscriber(object):
11 | def __init__(self, callback):
12 | self.callback = callback
13 | self.stop_signal = None
14 | threading.Thread(target = self.start, daemon = True).start()
15 |
16 | def __del__(self):
17 | self.stop_signal = True
18 |
19 | def unregister(self):
20 | self.stop_signal = True
21 |
22 | def start(self):
23 | re_field = re.compile("(^ *PID|USER +| *%CPU| *%MEM|COMMAND.*)")
24 |
25 | self.stop_signal = None
26 | try:
27 | while not self.stop_signal:
28 | lines = subprocess.check_output(['top', '-bn', '1']).decode('utf-8').split("\n")
29 |
30 | fields = None
31 | output = []
32 |
33 | for line in lines:
34 | if len(line.strip()) == 0:
35 | continue
36 |
37 | if "PID" in line and "%CPU" in line and "%MEM" in line and "COMMAND" in line and "USER" in line:
38 | fields = {}
39 | for m in re_field.finditer(line):
40 | fields[m.group().strip()] = (m.start(), m.end())
41 | continue
42 |
43 | if fields is None:
44 | continue
45 | output.append({
46 | "pid": int(line[fields["PID"][0] : fields["PID"][1]]),
47 | "user": line[fields["USER"][0] : fields["USER"][1]].strip(),
48 | "cpu": float(line[fields["%CPU"][0] : fields["%CPU"][1]].replace(',','.')),
49 | "mem": float(line[fields["%MEM"][0] : fields["%MEM"][1]].replace(',','.')),
50 | "command": line[fields["COMMAND"][0] : ].strip(),
51 | })
52 |
53 | self.callback(output)
54 | time.sleep(2)
55 | except:
56 | traceback.print_exc()
57 |
58 | if __name__ == "__main__":
59 | # Run test
60 | ProcessesSubscriber(lambda msg: print("Received msg: %s" % msg))
61 | time.sleep(100)
62 |
--------------------------------------------------------------------------------
/rosboard/subscribers/system_stats_subscriber.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | try:
4 | import psutil
5 | except (ImportError, ModuleNotFoundError) as e:
6 | psutil = None
7 |
8 | import time
9 | import threading
10 | import traceback
11 |
12 | def mean(list):
13 | return sum(list)/len(list)
14 |
15 | class SystemStatsSubscriber(object):
16 | def __init__(self, callback):
17 | self.callback = callback
18 | self.stop = False
19 | threading.Thread(target = self.start, daemon = True).start()
20 |
21 | def __del__(self):
22 | self.stop = True
23 | pass
24 |
25 | def unregister(self):
26 | self.stop = True
27 | pass
28 |
29 | def start(self):
30 | if psutil is None:
31 | self.callback({"_error": "Please install psutil (sudo pip3 install --upgrade psutil) to use this feature."})
32 | return
33 |
34 | while not self.stop:
35 | try:
36 | p = psutil.Process()
37 |
38 | with p.oneshot():
39 | sensors_temperatures = psutil.sensors_temperatures()
40 | cpu_percent = psutil.cpu_percent(percpu = True)
41 | net_io_counters = psutil.net_io_counters()
42 | virtual_memory = psutil.virtual_memory()
43 | swap_memory = psutil.swap_memory()
44 | disk_usage = psutil.disk_usage('/')
45 |
46 | status = {}
47 |
48 | status["cpu_percent"] = cpu_percent
49 |
50 | if "coretemp" in sensors_temperatures:
51 | status["temp_coretemp"] = mean(list(map(
52 | lambda x:x.current,
53 | sensors_temperatures["coretemp"]
54 | )))
55 |
56 | status["net_bytes_sent"] = net_io_counters.bytes_sent
57 | status["net_bytes_recv"] = net_io_counters.bytes_recv
58 | status["disk_usage_percent"] = disk_usage.percent
59 | status["virtual_memory_percent"] = virtual_memory.percent
60 | status["swap_memory_percent"] = swap_memory.percent
61 |
62 | except Exception as e:
63 | traceback.print_exc()
64 |
65 | self.callback(status)
66 | time.sleep(3)
67 |
68 | if __name__ == "__main__":
69 | # Run test
70 | SystemStatsSubscriber(lambda msg: print("Received msg: %s" % msg))
71 | time.sleep(100)
72 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/ImageViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | class ImageViewer extends Viewer {
4 | /**
5 | * Gets called when Viewer is first initialized.
6 | * @override
7 | **/
8 | onCreate() {
9 | this.viewerNode = $('')
10 | .css({'font-size': '11pt'})
11 | .appendTo(this.card.content);
12 |
13 | this.img = $('
')
14 | .css({"width": "100%"})
15 | .appendTo(this.viewerNode);
16 |
17 | let that = this;
18 |
19 | this.img[0].addEventListener('pointermove', function(e) {
20 | if(!that.lastMsg) return;
21 | if(!that.img[0].clientWidth || !that.img[0].clientHeight) return;
22 |
23 | let width = that.img[0].naturalWidth;
24 | let height = that.img[0].naturalHeight;
25 | if(that.lastMsg._data_shape) {
26 | height = that.lastMsg._data_shape[0];
27 | width = that.lastMsg._data_shape[1];
28 | }
29 | let x = e.offsetX / that.img[0].clientWidth * width;
30 | let y = e.offsetY / that.img[0].clientHeight * height;
31 | x = Math.min(Math.max(x, 0), width);
32 | y = Math.min(Math.max(y, 0), height);
33 | that.tip("(" + x.toFixed(0) + ", " + y.toFixed(0) + ")");
34 | });
35 |
36 | this.img[0].addEventListener('pointerdown', function(e) {
37 | if(!that.lastMsg) return;
38 | if(!that.img[0].clientWidth || !that.img[0].clientHeight) return;
39 |
40 | let width = that.img[0].naturalWidth;
41 | let height = that.img[0].naturalHeight;
42 | if(that.lastMsg._data_shape) {
43 | height = that.lastMsg._data_shape[0];
44 | width = that.lastMsg._data_shape[1];
45 | }
46 | let x = e.offsetX / that.img[0].clientWidth * width;
47 | let y = e.offsetY / that.img[0].clientHeight * height;
48 | console.log("clicked at " + x + ", " + y);
49 | });
50 |
51 | this.lastMsg = null;
52 |
53 | super.onCreate();
54 | }
55 |
56 | onData(msg) {
57 | this.card.title.text(msg._topic_name);
58 |
59 | if(msg.__comp) {
60 | this.decodeAndRenderCompressed(msg);
61 | } else {
62 | this.decodeAndRenderUncompressed(msg);
63 | }
64 | }
65 |
66 | decodeAndRenderCompressed(msg) {
67 | this.img[0].src = "data:image/jpeg;base64," + msg._data_jpeg;
68 | this.lastMsg = msg;
69 | }
70 |
71 | decodeAndRenderUncompressed(msg) {
72 | this.error("Support for uncompressed images not yet implemented.");
73 | }
74 | }
75 |
76 | ImageViewer.friendlyName = "Image";
77 |
78 | ImageViewer.supportedTypes = [
79 | "sensor_msgs/msg/Image",
80 | "sensor_msgs/msg/CompressedImage",
81 | "nav_msgs/msg/OccupancyGrid",
82 | ];
83 |
84 | ImageViewer.maxUpdateRate = 24.0;
85 |
86 | Viewer.registerViewer(ImageViewer);
--------------------------------------------------------------------------------
/rosboard/html/index.html:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 | ROSboard
25 |
26 |
27 |
52 |
53 |
57 |
58 |
59 |
60 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/ProcessListViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // Viewer for _top (process list, non-ros)
4 |
5 | class ProcessListViewer extends Viewer {
6 | /**
7 | * Gets called when Viewer is first initialized.
8 | * @override
9 | **/
10 | onCreate() {
11 | this.card.title.text("ProcessListViewer");
12 |
13 | // wrapper and wrapper2 are css BS that are necessary to
14 | // have something that is 100% width but fixed aspect ratio
15 | this.wrapper = $('')
16 | .css({
17 | "position": "relative",
18 | "width": "100%",
19 | })
20 | .appendTo(this.card.content);
21 |
22 | this.wrapper2 = $('')
23 | .css({
24 | "width": "100%",
25 | "padding-bottom": "80%",
26 | "position": "relative",
27 | "overflow-x": "hidden",
28 | "overflow-y": "scroll",
29 | })
30 | .appendTo(this.wrapper);
31 |
32 | // actual log container, put it inside wrapper2
33 | this.processTable = $('')
34 | .addClass('mdl-data-table')
35 | .addClass('mdl-data-table-compact')
36 | .addClass('mdl-js-data-table')
37 | .css({
38 | "table-layout": "fixed",
39 | "position": "absolute",
40 | "width": "100%",
41 | "height": "100%",
42 | "font-size": "10pt",
43 | "line-height": "1.4em",
44 | "overflow-y": "hidden",
45 | "overflow-x": "hidden",
46 | })
47 | .appendTo(this.wrapper2);
48 |
49 | super.onCreate();
50 | }
51 |
52 | onData(msg) {
53 | this.card.title.text(msg._topic_name);
54 |
55 | // use vanilla JS here for speed, jQuery is slow
56 |
57 | this.processTable.innerHTML = "";
58 |
59 | let html = "";
60 | html += '| PID | CPU | MEM | USER | COMMAND |
';
61 |
62 | for(let i in msg.processes) {
63 | if(i>50) {
64 | html += "| Process list truncated. |
";
65 | break;
66 | }
67 | let process = msg.processes[i];
68 | html += "| " + process.pid + " | " + process.cpu + " | " + process.mem + " | " + process.user + " | " + process.command + " |
";
69 | }
70 | this.processTable[0].innerHTML = html;
71 | }
72 | }
73 |
74 | ProcessListViewer.friendlyName = "Process list";
75 |
76 | ProcessListViewer.supportedTypes = [
77 | "rosboard_msgs/msg/ProcessList",
78 | ];
79 |
80 | Viewer.registerViewer(ProcessListViewer);
81 |
--------------------------------------------------------------------------------
/rosboard/html/js/transports/WebSocketV1Transport.js:
--------------------------------------------------------------------------------
1 | class WebSocketV1Transport {
2 | constructor({path, onOpen, onClose, onRosMsg, onTopics, onSystem}) {
3 | this.path = path;
4 | this.onOpen = onOpen ? onOpen.bind(this) : null;
5 | this.onClose = onClose ? onClose.bind(this) : null;
6 | this.onMsg = onMsg ? onMsg.bind(this) : null;
7 | this.onTopics = onTopics ? onTopics.bind(this) : null;
8 | this.onSystem = onSystem ? onSystem.bind(this) : null;
9 | this.ws = null;
10 | }
11 |
12 | connect() {
13 | var protocolPrefix = (window.location.protocol === 'https:') ? 'wss:' : 'ws:';
14 | let abspath = protocolPrefix + '//' + location.host + this.path;
15 |
16 | let that = this;
17 |
18 | this.ws = new WebSocket(abspath);
19 |
20 | this.ws.onopen = function(){
21 | console.log("connected");
22 | if(that.onOpen) that.onOpen(that);
23 | }
24 |
25 | this.ws.onclose = function(){
26 | console.log("disconnected");
27 | if(that.onClose) that.onClose(that);
28 | }
29 |
30 | this.ws.onmessage = function(wsmsg) {
31 | let data = [];
32 | try {
33 | // try fast native parser
34 | data = JSON.parse(wsmsg.data);
35 | } catch(e) {
36 | // Python may have included Infinity, -Infinity, NaN
37 | // fall back to a JSON5 parsers which will deal with these well but is almost 50X slower in Chrome
38 | data = JSON5.parse(wsmsg.data);
39 | }
40 |
41 | let wsMsgType = data[0];
42 |
43 | if(wsMsgType === WebSocketV1Transport.MSG_PING) {
44 | this.send(JSON.stringify([WebSocketV1Transport.MSG_PONG, {
45 | [WebSocketV1Transport.PONG_SEQ]: data[1][WebSocketV1Transport.PING_SEQ],
46 | [WebSocketV1Transport.PONG_TIME]: Date.now(),
47 | }]));
48 | }
49 | else if(wsMsgType === WebSocketV1Transport.MSG_MSG && that.onMsg) that.onMsg(data[1]);
50 | else if(wsMsgType === WebSocketV1Transport.MSG_TOPICS && that.onTopics) that.onTopics(data[1]);
51 | else if(wsMsgType === WebSocketV1Transport.MSG_SYSTEM && that.onSystem) that.onSystem(data[1]);
52 | else console.log("received unknown message: " + wsmsg.data);
53 | }
54 | }
55 |
56 | isConnected() {
57 | return (this.ws && this.ws.readyState === this.ws.OPEN);
58 | }
59 |
60 | subscribe({topicName, maxUpdateRate = 24.0}) {
61 | this.ws.send(JSON.stringify([WebSocketV1Transport.MSG_SUB, {topicName: topicName, maxUpdateRate: maxUpdateRate}]));
62 | }
63 |
64 | unsubscribe({topicName}) {
65 | this.ws.send(JSON.stringify([WebSocketV1Transport.MSG_UNSUB, {topicName: topicName}]));
66 | }
67 | }
68 |
69 | WebSocketV1Transport.MSG_PING = "p";
70 | WebSocketV1Transport.MSG_PONG = "q";
71 | WebSocketV1Transport.MSG_MSG = "m";
72 | WebSocketV1Transport.MSG_TOPICS = "t";
73 | WebSocketV1Transport.MSG_SUB = "s";
74 | WebSocketV1Transport.MSG_SYSTEM = "y";
75 | WebSocketV1Transport.MSG_UNSUB = "u";
76 |
77 | WebSocketV1Transport.PING_SEQ= "s";
78 | WebSocketV1Transport.PONG_SEQ = "s";
79 | WebSocketV1Transport.PONG_TIME = "t";
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/GenericViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // GenericViewer just displays message fields and values in a table.
4 | // It can be used on any ROS type.
5 |
6 | class GenericViewer extends Viewer {
7 | /**
8 | * Gets called when Viewer is first initialized.
9 | * @override
10 | **/
11 | onCreate() {
12 | this.viewerNode = $('')
13 | .css({'font-size': '11pt'})
14 | .appendTo(this.card.content);
15 |
16 | this.viewerNodeFadeTimeout = null;
17 |
18 | this.expandFields = { };
19 | this.fieldNodes = { };
20 | this.dataTable = $('')
21 | .addClass('mdl-data-table')
22 | .addClass('mdl-js-data-table')
23 | .css({'width': '100%', 'min-height': '30pt', 'table-layout': 'fixed' })
24 | .appendTo(this.viewerNode);
25 |
26 | super.onCreate();
27 | }
28 |
29 | onData(data) {
30 | this.card.title.text(data._topic_name);
31 |
32 | for(let field in data) {
33 | if(field[0] === "_") continue;
34 | // if(field === "header") continue;
35 | // if(field === "name") continue;
36 |
37 | if(!this.fieldNodes[field]) {
38 | let tr = $('
')
39 | .appendTo(this.dataTable);
40 | $(' | ')
41 | .addClass('mdl-data-table__cell--non-numeric')
42 | .text(field)
43 | .css({'width': '40%', 'font-weight': 'bold', 'overflow': 'hidden', 'text-overflow': 'ellipsis'})
44 | .appendTo(tr);
45 | this.fieldNodes[field] = $(' | ')
46 | .addClass('mdl-data-table__cell--non-numeric')
47 | .addClass('monospace')
48 | .css({'overflow': 'hidden', 'text-overflow': 'ellipsis'})
49 | .appendTo(tr);
50 | let that = this;
51 | this.fieldNodes[field].click(() => {that.expandFields[field] = !that.expandFields[field]; });
52 | }
53 |
54 | if(data[field].uuid) {
55 | this.fieldNodes[field].text(data[field].uuid.map((byte) => ((byte<16) ? "0": "") + (byte & 0xFF).toString(16)).join(''));
56 | this.fieldNodes[field].css({"color": "#808080"});
57 | continue;
58 | }
59 |
60 | if(typeof(data[field])==="boolean") {
61 | if(data[field] === true) {
62 | this.fieldNodes[field].text("true");
63 | this.fieldNodes[field].css({"color": "#80ff80"});
64 | } else {
65 | this.fieldNodes[field].text("false");
66 | this.fieldNodes[field].css({"color": "#ff8080"});
67 | }
68 | continue;
69 | }
70 |
71 | if(data.__comp && data.__comp.includes(field)) {
72 | this.fieldNodes[field][0].innerHTML = "(compressed)";
73 | continue;
74 | }
75 |
76 | if(this.expandFields[field]) {
77 | this.fieldNodes[field][0].innerHTML = (
78 | JSON.stringify(data[field], null, ' ')
79 | .replace(/\n/g, "
")
80 | .replace(/ /g, " ")
81 | );
82 | } else {
83 | this.fieldNodes[field][0].innerHTML = JSON.stringify(data[field], null, ' ');
84 | }
85 | }
86 | }
87 | }
88 |
89 | GenericViewer.friendlyName = "Raw data";
90 |
91 | GenericViewer.supportedTypes = [
92 | "*",
93 | ];
94 |
95 | Viewer.registerViewer(GenericViewer);
--------------------------------------------------------------------------------
/rosboard/message_serialization.py:
--------------------------------------------------------------------------------
1 | import array
2 | import base64
3 | import numpy as np
4 | import rosboard.serialization
5 |
6 | def ros2dict(msg):
7 | """
8 | Converts an arbitrary ROS1/ROS2 message into a JSON-serializable dict.
9 | """
10 | if type(msg) in (str, bool, int, float):
11 | return msg
12 |
13 | if type(msg) is tuple:
14 | return list(msg)
15 |
16 | if type(msg) is bytes:
17 | return base64.b64encode(msg).decode()
18 |
19 | output = {}
20 |
21 | if hasattr(msg, "get_fields_and_field_types"): # ROS2
22 | fields_and_field_types = msg.get_fields_and_field_types()
23 | elif hasattr(msg, "__slots__"): # ROS1
24 | fields_and_field_types = msg.__slots__
25 | else:
26 | raise ValueError("ros2dict: Does not appear to be a simple type or a ROS message: %s" % str(msg))
27 |
28 | for field in fields_and_field_types:
29 |
30 | # CompressedImage: compress to jpeg
31 | if (msg.__module__ == "sensor_msgs.msg._CompressedImage" or \
32 | msg.__module__ == "sensor_msgs.msg._compressed_image") \
33 | and field == "data":
34 | rosboard.compression.compress_compressed_image(msg, output)
35 | continue
36 |
37 | # Image: compress to jpeg
38 | if (msg.__module__ == "sensor_msgs.msg._Image" or \
39 | msg.__module__ == "sensor_msgs.msg._image") \
40 | and field == "data":
41 | rosboard.compression.compress_image(msg, output)
42 | continue
43 |
44 | # OccupancyGrid: render and compress to jpeg
45 | if (msg.__module__ == "nav_msgs.msg._OccupancyGrid" or \
46 | msg.__module__ == "nav_msgs.msg._occupancy_grid") \
47 | and field == "data":
48 | rosboard.compression.compress_occupancy_grid(msg, output)
49 | continue
50 |
51 | # LaserScan: strip to 3 decimal places (1mm precision) to reduce JSON size
52 | if (msg.__module__ == "sensor_msgs.msg._LaserScan" or \
53 | msg.__module__ == "sensor_msgs.msg._laser_scan") \
54 | and field == "ranges":
55 | output["ranges"] = list(map(lambda x: round(x, 3), msg.ranges))
56 | continue
57 |
58 | # PointCloud2: extract only necessary fields, reduce precision
59 | if (msg.__module__ == "sensor_msgs.msg._PointCloud2" or \
60 | msg.__module__ == "sensor_msgs.msg._point_cloud2") \
61 | and field == "data":
62 | rosboard.compression.compress_point_cloud2(msg, output)
63 | continue
64 |
65 | value = getattr(msg, field)
66 | if type(value) in (str, bool, int, float):
67 | output[field] = value
68 |
69 | elif type(value) is bytes:
70 | output[field] = base64.b64encode(value).decode()
71 |
72 | elif type(value) is tuple:
73 | output[field] = list(value)
74 |
75 | elif type(value) is list:
76 | output[field] = [ros2dict(el) for el in value]
77 |
78 | elif type(value) in (np.ndarray, array.array):
79 | output[field] = value.tolist()
80 |
81 | else:
82 | output[field] = ros2dict(value)
83 |
84 | return output
85 |
86 | if __name__ == "__main__":
87 | # Run unit tests
88 | print("str")
89 | print(ros2dict("test"))
90 | print("Path")
91 | from nav_msgs.msg import Path
92 | print(ros2dict(Path()))
93 | print("NavSatFix")
94 | from sensor_msgs.msg import NavSatFix
95 | print(ros2dict(NavSatFix()))
96 | print("Int32MultiArray")
97 | from std_msgs.msg import Int32MultiArray
98 | print(ros2dict(Int32MultiArray()))
99 | print("object (this should not work)")
100 | try:
101 | print(ros2dict(object()))
102 | except ValueError:
103 | print("exception successfully caught")
104 | print("all tests completed successfully")
105 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/LogViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // Viewer for /rosout and other logs that can be expressed in
4 | // rcl_interfaces/msgs/Log format.
5 |
6 | class LogViewer extends Viewer {
7 | /**
8 | * Gets called when Viewer is first initialized.
9 | * @override
10 | **/
11 | onCreate() {
12 | this.card.title.text("LogViewer");
13 |
14 | // wrapper and wrapper2 are css BS that are necessary to
15 | // have something that is 100% width but fixed aspect ratio
16 | this.wrapper = $('')
17 | .css({
18 | "position": "relative",
19 | "width": "100%",
20 | })
21 | .appendTo(this.card.content);
22 |
23 | this.wrapper2 = $('')
24 | .css({
25 | "width": "100%",
26 | "padding-bottom": "80%",
27 | "background": "#101010",
28 | "position": "relative",
29 | "overflow": "hidden",
30 | })
31 | .appendTo(this.wrapper);
32 |
33 | // actual log container, put it inside wrapper2
34 | this.logContainer = $('')
35 | .addClass("monospace")
36 | .css({
37 | "position": "absolute",
38 | "width": "100%",
39 | "height": "100%",
40 | "font-size": "7pt",
41 | "line-height": "1.4em",
42 | "overflow-y": "hidden",
43 | "overflow-x": "hidden",
44 | })
45 | .appendTo(this.wrapper2);
46 |
47 | // add the first log
48 | $('')
49 | .text("Logs will appear here.")
50 | .appendTo(this.logContainer);
51 |
52 | super.onCreate();
53 |
54 | let that = this;
55 | this.logScrollTimeout = setTimeout(() => {
56 | that.logContainer[0].scrollTop = that.logContainer[0].scrollHeight;
57 | }, 1000);
58 | }
59 |
60 | onData(msg) {
61 | while(this.logContainer.children().length > 30) {
62 | this.logContainer.children()[0].remove();
63 | }
64 |
65 | this.card.title.text(msg._topic_name);
66 |
67 | let color = "#c0c0c0"; // default color
68 | let level_text = "";
69 |
70 | // set colors based on log level, if defined
71 | // 10-20-30-40-50 is ROS2, 1-2-4-8-16 is ROS1
72 | if(msg.level === 10 || msg.level === 1) { level_text = "DEBUG"; color = "#00a000"; }
73 | if(msg.level === 20 || msg.level === 2) { level_text = "INFO"; color = "#a0a0a0"; }
74 | if(msg.level === 30 || msg.level === 4) { level_text = "WARN"; color = "#c0c000"; }
75 | if(msg.level === 40 || msg.level === 8) { level_text = "ERROR"; color = "#ff4040"; }
76 | if(msg.level === 50 || msg.level === 16) { level_text = "FATAL"; color = "#ff0000"; }
77 |
78 | let text = "";
79 | if(level_text !== "") text += "[" + level_text + "] "
80 | if(msg.name) text += "[" + msg.name + "] ";
81 | text += msg.msg;
82 |
83 | text = text
84 | .replace(/&/g, "&")
85 | .replace(//g, ">")
87 | .replace(/"/g, """)
88 | .replace(/'/g, "'")
89 | .replace(/\n/g, "
\n")
90 | .replace(/(\[[0-9\.]*\])/g, '$1');
91 |
92 | $('')
93 | .html(text)
94 | .css({ "color": color })
95 | .appendTo(this.logContainer);
96 |
97 | this.logContainer[0].scrollTop = this.logContainer[0].scrollHeight;
98 | }
99 | }
100 |
101 | LogViewer.friendlyName = "Log view";
102 |
103 | LogViewer.supportedTypes = [
104 | "rcl_interfaces/msg/Log",
105 | "rosgraph_msgs/msg/Log",
106 | ];
107 |
108 | Viewer.registerViewer(LogViewer);
--------------------------------------------------------------------------------
/rosboard/serialization.py:
--------------------------------------------------------------------------------
1 | import array
2 | import base64
3 | import numpy as np
4 | import rosboard.compression
5 |
6 | def ros2dict(msg):
7 | """
8 | Converts an arbitrary ROS1/ROS2 message into a JSON-serializable dict.
9 | """
10 | if type(msg) in (str, bool, int, float):
11 | return msg
12 |
13 | if type(msg) is tuple:
14 | return list(msg)
15 |
16 | if type(msg) is bytes:
17 | return base64.b64encode(msg).decode()
18 |
19 | output = {}
20 |
21 | if hasattr(msg, "get_fields_and_field_types"): # ROS2
22 | fields_and_field_types = msg.get_fields_and_field_types()
23 | elif hasattr(msg, "__slots__"): # ROS1
24 | fields_and_field_types = msg.__slots__
25 | else:
26 | raise ValueError("ros2dict: Does not appear to be a simple type or a ROS message: %s" % str(msg))
27 |
28 | for field in fields_and_field_types:
29 |
30 | # CompressedImage: compress to jpeg
31 | if (msg.__module__ == "sensor_msgs.msg._CompressedImage" or \
32 | msg.__module__ == "sensor_msgs.msg._compressed_image") \
33 | and field == "data":
34 | rosboard.compression.compress_compressed_image(msg, output)
35 | continue
36 |
37 | # Image: compress to jpeg
38 | if (msg.__module__ == "sensor_msgs.msg._Image" or \
39 | msg.__module__ == "sensor_msgs.msg._image") \
40 | and field == "data":
41 | rosboard.compression.compress_image(msg, output)
42 | continue
43 |
44 | # OccupancyGrid: render and compress to jpeg
45 | if (msg.__module__ == "nav_msgs.msg._OccupancyGrid" or \
46 | msg.__module__ == "nav_msgs.msg._occupancy_grid") \
47 | and field == "data":
48 | rosboard.compression.compress_occupancy_grid(msg, output)
49 | continue
50 |
51 | # LaserScan: reduce precision
52 | if (msg.__module__ == "sensor_msgs.msg._LaserScan" or \
53 | msg.__module__ == "sensor_msgs.msg._laser_scan") \
54 | and field == "ranges":
55 | rosboard.compression.compress_laser_scan(msg, output)
56 | continue
57 | if (msg.__module__ == "sensor_msgs.msg._LaserScan" or \
58 | msg.__module__ == "sensor_msgs.msg._laser_scan") \
59 | and field == "intensities":
60 | continue
61 |
62 | # PointCloud2: extract only necessary fields, reduce precision
63 | if (msg.__module__ == "sensor_msgs.msg._PointCloud2" or \
64 | msg.__module__ == "sensor_msgs.msg._point_cloud2") \
65 | and field == "data" and msg.data:
66 | rosboard.compression.compress_point_cloud2(msg, output)
67 | continue
68 |
69 | value = getattr(msg, field)
70 | if type(value) in (str, bool, int, float):
71 | output[field] = value
72 |
73 | elif type(value) is bytes:
74 | output[field] = base64.b64encode(value).decode()
75 |
76 | elif type(value) is tuple:
77 | output[field] = list(value)
78 |
79 | elif type(value) is list:
80 | output[field] = [ros2dict(el) for el in value]
81 |
82 | elif type(value) in (np.ndarray, array.array):
83 | output[field] = value.tolist()
84 |
85 | else:
86 | output[field] = ros2dict(value)
87 |
88 | return output
89 |
90 | if __name__ == "__main__":
91 | # Run unit tests
92 | print("str")
93 | print(ros2dict("test"))
94 | print("Path")
95 | from nav_msgs.msg import Path
96 | print(ros2dict(Path()))
97 | print("NavSatFix")
98 | from sensor_msgs.msg import NavSatFix
99 | print(ros2dict(NavSatFix()))
100 | print("Int32MultiArray")
101 | from std_msgs.msg import Int32MultiArray
102 | print(ros2dict(Int32MultiArray()))
103 | print("object (this should not work)")
104 | try:
105 | print(ros2dict(object()))
106 | except ValueError:
107 | print("exception successfully caught")
108 | print("all tests completed successfully")
109 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/TimeSeriesPlotViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // Plots time series data of a single .data variable.
4 | // Works on all ROS single value std_msgs types.
5 |
6 | class TimeSeriesPlotViewer extends Viewer {
7 | /**
8 | * Gets called when Viewer is first initialized.
9 | * @override
10 | **/
11 | onCreate() {
12 | this.viewerNode = $('')
13 | .css({'font-size': '11pt'})
14 | .appendTo(this.card.content);
15 |
16 | this.plotNode = $('')
17 | .appendTo(this.viewerNode);
18 |
19 | this.dataTable = $('')
20 | .addClass('mdl-data-table')
21 | .addClass('mdl-js-data-table')
22 | .css({'width': '100%', 'table-layout': 'fixed' })
23 | .appendTo(this.viewerNode);
24 |
25 | let tr = $('
')
26 | .appendTo(this.dataTable);
27 |
28 | $(' | ')
29 | .addClass('mdl-data-table__cell--non-numeric')
30 | .text("data")
31 | .css({'width': '40%', 'font-weight': 'bold', 'overflow': 'hidden', 'text-overflow': 'ellipsis'})
32 | .appendTo(tr);
33 | this.valueField = $(' | ')
34 | .addClass('mdl-data-table__cell--non-numeric')
35 | .addClass('monospace')
36 | .css({'overflow': 'hidden', 'text-overflow': 'ellipsis'})
37 | .appendTo(tr);
38 |
39 | this.lastData = {};
40 |
41 | let opts = {
42 | id: "chart1",
43 | class: "my-chart",
44 | width: 300,
45 | height: 200,
46 | legend: {
47 | show: false,
48 | },
49 | axes: [
50 | {
51 | stroke: "#a0a0a0",
52 | ticks: {
53 | stroke: "#404040",
54 | },
55 | grid: {
56 | stroke: "#404040",
57 | },
58 | },
59 | {
60 | stroke: "#a0a0a0",
61 | ticks: {
62 | stroke: "#404040",
63 | },
64 | grid: {
65 | stroke: "#404040",
66 | },
67 | },
68 | ],
69 | series: [
70 | {},
71 | {
72 | show: true,
73 | spanGaps: false,
74 | stroke: "#00c080",
75 | width: 1,
76 | }
77 | ],
78 | };
79 |
80 | this.size = 500;
81 | this.data = [
82 | new Array(this.size).fill(0),
83 | new Array(this.size).fill(0),
84 | ];
85 |
86 | this.ptr = 0;
87 |
88 | this.uplot = new uPlot(opts, this.data, this.plotNode[0]);
89 |
90 | setInterval(()=> {
91 | let data = [];
92 | if(this.data[0][this.ptr] === 0) {
93 | data = [
94 | this.data[0].slice(0, this.ptr),
95 | this.data[1].slice(0, this.ptr),
96 | ];
97 | } else {
98 | data = [
99 | this.data[0].slice(this.ptr, this.size).concat(this.data[0].slice(0, this.ptr)),
100 | this.data[1].slice(this.ptr, this.size).concat(this.data[1].slice(0, this.ptr)),
101 | ];
102 | }
103 | this.uplot.setSize({width:this.plotNode[0].clientWidth, height:200});
104 | this.uplot.setData(data);
105 | }, 200);
106 |
107 | super.onCreate();
108 | }
109 |
110 | onData(msg) {
111 | this.card.title.text(msg._topic_name);
112 | this.valueField.text(msg.data);
113 | this.data[0][this.ptr] = Math.floor(Date.now() / 10)/ 100;
114 | this.data[1][this.ptr] = msg.data;
115 | this.ptr = (this.ptr + 1) % this.size;
116 | }
117 | }
118 |
119 | TimeSeriesPlotViewer.friendlyName = "Time series plot";
120 |
121 | TimeSeriesPlotViewer.supportedTypes = [
122 | "std_msgs/msg/Bool",
123 | "std_msgs/msg/Byte",
124 | "std_msgs/msg/Char",
125 | "std_msgs/msg/Int8",
126 | "std_msgs/msg/Int16",
127 | "std_msgs/msg/Int32",
128 | "std_msgs/msg/Int64",
129 | "std_msgs/msg/UInt8",
130 | "std_msgs/msg/UInt16",
131 | "std_msgs/msg/UInt32",
132 | "std_msgs/msg/UInt64",
133 | "std_msgs/msg/Float32",
134 | "std_msgs/msg/Float64",
135 | ];
136 |
137 | TimeSeriesPlotViewer.maxUpdateRate = 100.0;
138 |
139 | Viewer.registerViewer(TimeSeriesPlotViewer);
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | BSD 3-Clause License
2 |
3 | Copyright (c) 2021, Dheera Venkatraman
4 | All rights reserved.
5 |
6 | Redistribution and use in source and binary forms, with or without
7 | modification, are permitted provided that the following conditions are met:
8 |
9 | 1. Redistributions of source code must retain the above copyright notice, this
10 | list of conditions and the following disclaimer.
11 |
12 | 2. Redistributions in binary form must reproduce the above copyright notice,
13 | this list of conditions and the following disclaimer in the documentation
14 | and/or other materials provided with the distribution.
15 |
16 | 3. Neither the name of the copyright holder nor the names of its
17 | contributors may be used to endorse or promote products derived from
18 | this software without specific prior written permission.
19 |
20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 |
31 | Portions of this software are copyright of their respective authors and released
32 | under their respective licenses:
33 |
34 | - Tornado:
35 | Used as a web server and web socket server.
36 | Copyright (C) The Tornado Authors
37 | Apache 2.0 License
38 | https://www.tornadoweb.org/
39 |
40 | - simplejpeg
41 | Used for encoding and decoding JPEG format.
42 | Copyright (C) Joachim Folz
43 | MIT License
44 | https://gitlab.com/jfolz/simplejpeg
45 |
46 | - Masonry
47 | JavaScript library used for laying out cards efficiently.
48 | Copyright (C) David DeSandro
49 | MIT License
50 | https://masonry.desandro.com/
51 |
52 | - Leaflet.js:
53 | Used for rendering sensor_msgs/NavSatFix messages
54 | Copyright (C) Vladimir Agafonkin
55 | CloudMade, BSD 2-clause license
56 | https://github.com/Leaflet/Leaflet
57 |
58 | - Material Design Lite:
59 | Used for general UI theming and widgets of the web-based client
60 | Copyright (C) Google, Inc.
61 | Apache 2.0 License
62 | https://getmdl.io/
63 |
64 | - jQuery:
65 | Used for client-side DOM manipulation
66 | Copyright (C) OpenJS Foundation
67 | MIT License
68 | https://jquery.com/
69 |
70 | - litegl.js
71 | Used for 3D visualizations as a WebGL wrapper
72 | Copyright (C) Evan Wallace, Javi Agenjo
73 | MIT License
74 | https://github.com/jagenjo/litegl.js/
75 |
76 | - glMatrix
77 | Matrix manipulations for 3D visualizations
78 | Copyright (C) Brandon Jones, Colin MacKenzie IV.
79 | MIT License
80 | https://github.com/toji/gl-matrix
81 |
82 | - rosbag.js:
83 | Used for reading ROS 1 .bag files
84 | Copyright (C) Cruise Automation
85 | MIT License
86 | https://github.com/cruise-automation/rosbag.js/
87 |
88 | - uPlot:
89 | Used for all time-series plots
90 | Copyright (C) Leon Sorokin
91 | MIT License
92 | https://github.com/leeoniya/uPlot
93 |
94 | - JSON5:
95 | Used for encoding/decoding JSON5 messages
96 | Copyright (C) Aseem Kishore, and others.
97 | MIT License
98 | https://github.com/json5/json5
99 |
100 | - JetBrains Mono:
101 | Used for all fixed-width text in the web UI
102 | Copyright (C) The JetBrains Mono Project Authors
103 | SIL Open Font License 1.1
104 | https://github.com/JetBrains/JetBrainsMono
105 |
106 | - Titillium Web:
107 | Used for all variable-width text in the web UI
108 | Copyright (C) Accademia di Belle Arti di Urbino and students of MA course of Visual design
109 | SIL Open Font License 1.1
110 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/LaserScanViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | class LaserScanViewer extends Space2DViewer {
4 | _base64decode(base64) {
5 | var binary_string = window.atob(base64);
6 | var len = binary_string.length;
7 | var bytes = new Uint8Array(len);
8 | for (var i = 0; i < len; i++) {
9 | bytes[i] = binary_string.charCodeAt(i);
10 | }
11 | return bytes.buffer;
12 | }
13 | onData(msg) {
14 | this.card.title.text(msg._topic_name);
15 |
16 | let points = null;
17 |
18 | if(msg.__comp) {
19 | points = this.decodeCompressed(msg);
20 | } else {
21 | points = this.decodeUncompressed(msg);
22 | }
23 |
24 | this.lastPoints = points;
25 |
26 | // send it to the plotter to display
27 | let drawObjects = ([
28 | {type: "path", data: [0, 0, 0, 1], color: "#00f060", lineWidth: 2}, // unit x axis visualization in red
29 | {type: "path", data: [0, 0, 1, 0], color: "#f06060", lineWidth: 2}, // unit y axis visualization in green
30 | {type: "points", data: points, color: "#e0e0e0"}, // the laserscan points to be plotted
31 | ]);
32 |
33 | if(this.highlightedPoint) {
34 | this.onSpace2DClick({x: this.highlightedPoint[0], y: this.highlightedPoint[1]});
35 | if(this.highlightedPoint) {
36 | drawObjects.push({
37 | type: "points",
38 | data: this.highlightedPoint,
39 | color: "#ff5000",
40 | });
41 | drawObjects.push({
42 | type: "text",
43 | text: " (" + this.highlightedPoint[0].toFixed(2) + ", " + this.highlightedPoint[1].toFixed(2) + ")",
44 | fontSize: 12,
45 | x: this.highlightedPoint[0],
46 | y: this.highlightedPoint[1],
47 | color: "#ff5000",
48 | });
49 | }
50 | }
51 |
52 | this.draw(drawObjects);
53 | }
54 |
55 | onSpace2DClick({x,y}) {
56 | if(!this.lastPoints) return;
57 | let closestx = -1.0;
58 | let closesty = -1.0;
59 | let closestDist = 1e12;
60 | for(let i=0;i')
10 | .css({'font-size': '11pt'})
11 | .appendTo(this.card.content);
12 |
13 | this.diagnosticStatuses = {};
14 |
15 | this.expandFields = { };
16 | this.fieldNodes = { };
17 | this.dataTables = { };
18 | /*this.dataTable = $('')
19 | .addClass('mdl-data-table')
20 | .addClass('mdl-js-data-table')
21 | .css({'width': '100%', 'min-height': '30pt', 'table-layout': 'fixed' })
22 | .appendTo(this.viewer);*/
23 |
24 | super.onCreate();
25 | }
26 |
27 | onData(msg) {
28 | this.card.title.text(msg._topic_name);
29 |
30 | for(let i in msg.status) {
31 | let idx_name = msg.status[i].name.split("/")[1];
32 | let status = {}
33 | if (this.diagnosticStatuses.hasOwnProperty(idx_name)) {
34 | status = this.diagnosticStatuses[idx_name];
35 | if (msg.status[i].level > status["_level"]) {
36 | status["_level"] = msg.status[i].level;
37 | status["_message"] = msg.status[i].message;
38 | }
39 | } else {
40 | status["_level"] = msg.status[i].level;
41 | status["_name"] = idx_name;
42 | status["_message"] = msg.status[i].message;
43 | status["_hardware_id"] = msg.status[i].hardware_id;
44 | }
45 | for(let j in msg.status[i].values) {
46 | status[msg.status[i].values[j].key] = msg.status[i].values[j].value;
47 | }
48 | this.diagnosticStatuses[status._name] = status;
49 | }
50 |
51 | for(let key in this.diagnosticStatuses) {
52 | if(!this.dataTables[key]) {
53 | this.dataTables[key] = $('')
54 | .addClass('mdl-data-table')
55 | .addClass('mdl-data-table-diagnostic')
56 | .addClass('mdl-js-data-table')
57 | .appendTo(this.viewer);
58 |
59 | this.dataTables[key].thead = $('')
60 | .appendTo(this.dataTables[key]);
61 | this.dataTables[key].headRow = $('
').appendTo(this.dataTables[key].thead);
62 | this.dataTables[key].icon = $('chevron_right | ').appendTo(this.dataTables[key].headRow);
63 | this.dataTables[key].hardwareIdDisplay = $('' + key + ' | ').appendTo(this.dataTables[key].headRow);
64 | this.dataTables[key].messageDisplay = $(' | ').appendTo(this.dataTables[key].headRow);
65 | this.dataTables[key].tbody = $("").appendTo(this.dataTables[key]).hide();
66 |
67 | let that = this;
68 | this.dataTables[key].thead[0].addEventListener('click', function(e) {
69 | that.dataTables[key].tbody.toggle();
70 | if(that.dataTables[key].icon.children('i').text() === "chevron_right") {
71 | that.dataTables[key].icon.children('i').text("expand_more");
72 | } else {
73 | that.dataTables[key].icon.children('i').text("chevron_right");
74 | }
75 | })
76 | }
77 |
78 | let status = this.diagnosticStatuses[key];
79 |
80 | this.dataTables[key].messageDisplay.text(status._message);
81 |
82 | if(status._level === 0) {
83 | this.dataTables[key].headRow.addClass("diagnostic-level-ok");
84 | this.dataTables[key].headRow.removeClass("diagnostic-level-warn");
85 | this.dataTables[key].headRow.removeClass("diagnostic-level-error");
86 | this.dataTables[key].headRow.removeClass("diagnostic-level-stale");
87 | } else if(status._level === 1) {
88 | this.dataTables[key].headRow.removeClass("diagnostic-level-ok");
89 | this.dataTables[key].headRow.addClass("diagnostic-level-warn");
90 | this.dataTables[key].headRow.removeClass("diagnostic-level-error");
91 | this.dataTables[key].headRow.removeClass("diagnostic-level-stale");
92 | } else if(status._level === 2) {
93 | this.dataTables[key].headRow.removeClass("diagnostic-level-ok");
94 | this.dataTables[key].headRow.removeClass("diagnostic-level-warn");
95 | this.dataTables[key].headRow.addClass("diagnostic-level-error");
96 | this.dataTables[key].headRow.removeClass("diagnostic-level-stale");
97 | } else if(status._level === 3) {
98 | this.dataTables[key].headRow.removeClass("diagnostic-level-ok");
99 | this.dataTables[key].headRow.removeClass("diagnostic-level-warn");
100 | this.dataTables[key].headRow.removeClass("diagnostic-level-error");
101 | this.dataTables[key].headRow.addClass("diagnostic-level-stale");
102 | }
103 |
104 | this.dataTables[key].tbody.empty();
105 | let html = "";
106 | for(let key in status) {
107 | if(key[0] === "_") continue;
108 | html += '| | ' + key + ' | ' + status[key] + " |
";
109 | }
110 | $(html).appendTo(this.dataTables[key].tbody);
111 | }
112 | }
113 | }
114 |
115 | DiagnosticViewer.friendlyName = "Aggregated diagnostics";
116 |
117 | DiagnosticViewer.supportedTypes = [
118 | "diagnostic_msgs/msg/DiagnosticArray",
119 | ];
120 |
121 | Viewer.registerViewer(DiagnosticViewer);
122 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/GeometryViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | class GeometryViewer extends Space2DViewer {
4 | _quatToEuler(q) {
5 | let euler = {};
6 |
7 | // roll (x-axis rotation)
8 | let sinr_cosp = 2 * (q.w * q.x + q.y * q.z);
9 | let cosr_cosp = 1 - 2 * (q.x * q.x + q.y * q.y);
10 | euler.roll = Math.atan2(sinr_cosp, cosr_cosp);
11 |
12 | // pitch (y-axis rotation)
13 | let sinp = 2 * (q.w * q.y - q.z * q.x);
14 | if (Math.abs(sinp) >= 1)
15 | euler.pitch = sinp > 0 ? (Math.PI/2) : (-Math.PI/2);
16 | else
17 | euler.pitch = Math.asin(sinp);
18 |
19 | // yaw (z-axis rotation)
20 | let siny_cosp = 2 * (q.w * q.z + q.x * q.y);
21 | let cosy_cosp = 1 - 2 * (q.y * q.y + q.z * q.z);
22 | euler.yaw = Math.atan2(siny_cosp, cosy_cosp);
23 |
24 | return euler;
25 | }
26 |
27 | onData(msg) {
28 | this.card.title.text(msg._topic_name);
29 |
30 | if(msg._topic_type.endsWith("/Pose")) { this.processPose(msg); return; }
31 | if(msg._topic_type.endsWith("/PoseStamped")) { this.processPoseStamped(msg); return; }
32 | if(msg._topic_type.endsWith("/PoseWithCovariance")) { this.processPoseWithCovariance(msg); return; }
33 | if(msg._topic_type.endsWith("/PoseWithCovarianceStamped")) { this.processPoseWithCovarianceStamped(msg); return; }
34 | if(msg._topic_type.endsWith("/Point")) { this.processPoint(msg); return; }
35 | if(msg._topic_type.endsWith("/Point32")) { this.processPoint(msg); return; }
36 | if(msg._topic_type.endsWith("/PointStamped")) { this.processPointStamped(msg); return; }
37 | if(msg._topic_type.endsWith("/Odometry")) { this.processOdometry(msg); return; }
38 | }
39 |
40 | processPose(msg) {
41 | let x = msg.position.x;
42 | let y = msg.position.y;
43 | let angles = this._quatToEuler(msg.orientation);
44 | this.renderTrackedPoseView({x: x, y: y, yaw: angles.yaw});
45 | }
46 |
47 | processPoseStamped(msg) {
48 | let x = msg.pose.position.x;
49 | let y = msg.pose.position.y;
50 | let angles = this._quatToEuler(msg.pose.orientation);
51 | this.renderTrackedPoseView({x: x, y: y, yaw: angles.yaw});
52 | }
53 |
54 | processPoseWithCovariance(msg) {
55 | let x = msg.pose.position.x;
56 | let y = msg.pose.position.y;
57 | let angles = this._quatToEuler(msg.pose.orientation);
58 | this.renderTrackedPoseView({x: x, y: y, yaw: angles.yaw});
59 | }
60 |
61 | processPoseWithCovarianceStamped(msg) {
62 | let x = msg.pose.pose.position.x;
63 | let y = msg.pose.pose.position.y;
64 | let angles = this._quatToEuler(msg.pose.pose.orientation);
65 | this.renderTrackedPoseView({x: x, y: y, yaw: angles.yaw});
66 | }
67 |
68 | processPoint(msg) {
69 | let x = msg.x;
70 | let y = msg.y;
71 | this.renderTrackedPoseView({x: x, y: y, yaw: null});
72 | }
73 |
74 | processPointStamped(msg) {
75 | let x = msg.point.x;
76 | let y = msg.point.y;
77 | this.renderTrackedPoseView({x:x, y:y, yaw: null});
78 | }
79 |
80 | processOdometry(msg) {
81 | let x = msg.pose.pose.position.x;
82 | let y = msg.pose.pose.position.y;
83 | let angles = this._quatToEuler(msg.pose.pose.orientation);
84 | this.renderTrackedPoseView({x: x, y: y, yaw: angles.yaw});
85 | }
86 |
87 | renderTrackedPoseView({x, y, yaw}) {
88 |
89 | if(!this.points) this.points = new Array(100).fill(NaN);
90 | if(!this.ptr) this.ptr = 0;
91 |
92 | this.points[this.ptr] = x;
93 | this.points[this.ptr+1] = y;
94 | this.ptr += 2;
95 | this.ptr = this.ptr % 1000;
96 |
97 | let pointsSlice = this.points.slice(this.ptr, 1000).concat(this.points.slice(0, this.ptr));
98 |
99 | // send it to the plotter to display
100 | let drawObjects = ([
101 | // x axis
102 | {type: "path", data: [0, 0, 0, 1], color: "#00f060", lineWidth: 2}, // unit x axis visualization in red
103 | // y axis
104 | {type: "path", data: [0, 0, 1, 0], color: "#f06060", lineWidth: 2}, // unit y axis visualization in green
105 | // the current point
106 | {type: "points", data: [x, y], color: "#ff5000"},
107 | // history path
108 | {type: "path", data: pointsSlice, color: "#808080"},
109 | ])
110 | if(yaw !== null) {
111 | drawObjects = drawObjects.concat([
112 | // arrow stem
113 | {type: "path", data: [
114 | x,
115 | y,
116 | x + 2*Math.cos(yaw),
117 | y + 2*Math.sin(yaw),
118 | ], color: "#ff5000", lineWidth: 1},
119 | // arrow head
120 | {type: "path", data: [
121 | x + 2*Math.cos(yaw) + 0.5*Math.cos(13*Math.PI/12+yaw),
122 | y + 2*Math.sin(yaw) + 0.5*Math.sin(13*Math.PI/12+yaw),
123 | x + 2*Math.cos(yaw),
124 | y + 2*Math.sin(yaw),
125 | x + 2*Math.cos(yaw) + 0.5*Math.cos(-13*Math.PI/12+yaw),
126 | y + 2*Math.sin(yaw) + 0.5*Math.sin(-13*Math.PI/12+yaw),
127 | ], color: "#ff5000", lineWidth: 1}
128 | ]);
129 | }
130 | this.setDefaultView({xcenter: x, ycenter: y, scale: 40.0});
131 | this.draw(drawObjects);
132 | }
133 | }
134 |
135 | GeometryViewer.friendlyName = "2D view";
136 |
137 | GeometryViewer.supportedTypes = [
138 | "geometry_msgs/msg/Pose",
139 | "geometry_msgs/msg/PoseStamped",
140 | "geometry_msgs/msg/PoseWithCovariance",
141 | "geometry_msgs/msg/PoseWithCovarianceStamped",
142 | "geometry_msgs/msg/Point",
143 | "geometry_msgs/msg/Point32",
144 | "geometry_msgs/msg/PointStamped",
145 | "nav_msgs/msg/Odometry",
146 | ];
147 |
148 | GeometryViewer.maxUpdateRate = 10.0;
149 |
150 | Viewer.registerViewer(GeometryViewer);
151 |
--------------------------------------------------------------------------------
/rosboard/html/js/eventemitter2.min.js:
--------------------------------------------------------------------------------
1 | !function(e){function r(){this._events={};if(this._conf){i.call(this,this._conf)}}function i(e){if(e){this._conf=e;e.delimiter&&(this.delimiter=e.delimiter);e.maxListeners&&(this._events.maxListeners=e.maxListeners);e.wildcard&&(this.wildcard=e.wildcard);e.newListener&&(this.newListener=e.newListener);if(this.wildcard){this.listenerTree={}}}}function s(e){this._events={};this.newListener=false;i.call(this,e)}function o(e,t,n,r){if(!n){return[]}var i=[],s,u,a,f,l,c,h,p=t.length,d=t[r],v=t[r+1];if(r===p&&n._listeners){if(typeof n._listeners==="function"){e&&e.push(n._listeners);return[n]}else{for(s=0,u=n._listeners.length;s0&&o._listeners.length>a){o._listeners.warned=true;console.error("(node) warning: possible EventEmitter memory "+"leak detected. %d listeners added. "+"Use emitter.setMaxListeners() to increase limit.",o._listeners.length);console.trace()}}}return true}u=e.shift()}return true}var t=Array.isArray?Array.isArray:function(t){return Object.prototype.toString.call(t)==="[object Array]"};var n=10;s.prototype.delimiter=".";s.prototype.setMaxListeners=function(e){this._events||r.call(this);this._events.maxListeners=e;if(!this._conf)this._conf={};this._conf.maxListeners=e};s.prototype.event="";s.prototype.once=function(e,t){this.many(e,1,t);return this};s.prototype.many=function(e,t,n){function i(){if(--t===0){r.off(e,i)}n.apply(this,arguments)}var r=this;if(typeof n!=="function"){throw new Error("many only accepts instances of Function")}i._origin=n;this.on(e,i);return r};s.prototype.emit=function(){this._events||r.call(this);var e=arguments[0];if(e==="newListener"&&!this.newListener){if(!this._events.newListener){return false}}if(this._all){var t=arguments.length;var n=new Array(t-1);for(var i=1;i1)switch(arguments.length){case 2:s.call(this,arguments[1]);break;case 3:s.call(this,arguments[1],arguments[2]);break;default:var t=arguments.length;var n=new Array(t-1);for(var i=1;i0||!!this._all}else{return!!this._all}};s.prototype.on=function(e,i){if(typeof e==="function"){this.onAny(e);return this}if(typeof i!=="function"){throw new Error("on only accepts instances of Function")}this._events||r.call(this);this.emit("newListener",e,i);if(this.wildcard){u.call(this,e,i);return this}if(!this._events[e]){this._events[e]=i}else if(typeof this._events[e]==="function"){this._events[e]=[this._events[e],i]}else if(t(this._events[e])){this._events[e].push(i);if(!this._events[e].warned){var s=n;if(typeof this._events.maxListeners!=="undefined"){s=this._events.maxListeners}if(s>0&&this._events[e].length>s){this._events[e].warned=true;console.error("(node) warning: possible EventEmitter memory "+"leak detected. %d listeners added. "+"Use emitter.setMaxListeners() to increase limit.",this._events[e].length);console.trace()}}}return this};s.prototype.onAny=function(e){if(typeof e!=="function"){throw new Error("onAny only accepts instances of Function")}if(!this._all){this._all=[]}this._all.push(e);return this};s.prototype.addListener=s.prototype.on;s.prototype.off=function(e,n){if(typeof n!=="function"){throw new Error("removeListener only takes instances of Function")}var r,i=[];if(this.wildcard){var s=typeof e==="string"?e.split(this.delimiter):e.slice();i=o.call(this,null,s,this.listenerTree,0)}else{if(!this._events[e])return this;r=this._events[e];i.push({_listeners:r})}for(var u=0;u0){r=this._all;for(t=0,n=r.length;t {return 0.0};
39 | }
40 | }
41 |
42 | onData(msg) {
43 | this.card.title.text(msg._topic_name);
44 |
45 | let points = null;
46 |
47 | if(msg.__comp) {
48 | points = this.decodeAndRenderCompressed(msg);
49 | } else {
50 | points = this.decodeAndRenderUncompressed(msg);
51 | }
52 |
53 | }
54 |
55 | decodeAndRenderCompressed(msg) {
56 | // decodes a uint16 lossy-compressed point cloud
57 | // basic explanation of algorithm:
58 | // - keep only x,y,z fields and throw away the rest
59 | // - throw away rows containing nans
60 | // - compress each number into a uint16 from 0 to 65535
61 | // where 0 is the minimum value over the whole set and 65535 is the max value over the set
62 | // so for example if the x values range from -95 m to 85 m, we encode x into a uint16 where
63 | // 0 represents -95 and 65535 represents 85
64 | // - provide the actual bounds (i.e. [-95, 85]) in a separate bounds field so it can be
65 | // scaled back correctly by the decompressor (this function)
66 |
67 | let bounds = msg._data_uint16.bounds;
68 | let points_data = this._base64decode(msg._data_uint16.points);
69 | let points_view = new DataView(points_data);
70 |
71 | let points = new Float32Array(Math.round(points_data.byteLength / 2));
72 |
73 | let xrange = bounds[1] - bounds[0];
74 | let xmin = bounds[0];
75 | let yrange = bounds[3] - bounds[2];
76 | let ymin = bounds[2];
77 | let zrange = bounds[5] - bounds[4];
78 | let zmin = bounds[4];
79 |
80 | for(let i=0; i {
102 | fields[field.name] = field;
103 | if(!field.datatype in PointCloud2Viewer.SIZEOF) {
104 | this.error("Invalid PointCloud2 message: field " + field + " has invalid datatype = " + String(field.datatype));
105 | return;
106 | }
107 | actualRecordSize += PointCloud2Viewer.SIZEOF[field.datatype];
108 | });
109 |
110 | if(!("x" in fields) || !("y") in fields) {
111 | this.error("Cannot display PointCloud2 message: Must have at least 'x' and 'y' fields or I don't know how to display it.");
112 | }
113 |
114 | let data = this._base64decode(msg.data);
115 |
116 | if(!(msg.point_step * msg.width * msg.height === data.byteLength)) {
117 | this.error("Invalid PointCloud2: failed assertion: point_step * width * height === data.length");
118 | return;
119 | }
120 |
121 | let points = new Float32Array(Math.round(data.byteLength / msg.point_step * 3));
122 | let view = new DataView(data);
123 | let littleEndian = !msg.is_bigendian;
124 |
125 | // cache these into variables to avoid hitting hash repeatedly
126 | let xOffset = fields["x"].offset;
127 | let xDataGetter = this._getDataGetter(fields["x"].datatype, view);
128 | let yOffset = fields["y"].offset;
129 | let yDataGetter = this._getDataGetter(fields["y"].datatype, view);
130 | let zOffset = -1;
131 | let zDataGetter = null;
132 | if("z" in fields) {
133 | zOffset = fields["z"].offset;
134 | zDataGetter = this._getDataGetter(fields["z"].datatype, view);
135 | }
136 |
137 | for(let i=0; i0&&(o+=" "+f(r));var u=[];return t.each(a,function(t,e){u.push(e+" "+o)}),u.join(", ")}function o(e,n){n||(t.cssNumber[e]=!0),t.transit.propertyMap[e]=d.transform,t.cssHooks[e]={get:function(n){var i=t(n).css("transit:transform");return i.get(e)},set:function(n,i){var r=t(n).css("transit:transform");r.setFromString(e,i),t(n).css({"transit:transform":r})}}}function u(t){return t.replace(/([A-Z])/g,function(t){return"-"+t.toLowerCase()})}function c(t,e){return"string"!=typeof t||t.match(/^[\-0-9\.]+$/)?""+t+e:t}function f(e){var n=e;return"string"!=typeof n||n.match(/^[\-0-9\.]+/)||(n=t.fx.speeds[n]||t.fx.speeds._default),c(n,"ms")}t.transit={version:"0.9.12",propertyMap:{marginLeft:"margin",marginRight:"margin",marginBottom:"margin",marginTop:"margin",paddingLeft:"padding",paddingRight:"padding",paddingBottom:"padding",paddingTop:"padding"},enabled:!0,useTransitionEnd:!1};var p=document.createElement("div"),d={},l=navigator.userAgent.toLowerCase().indexOf("chrome")>-1;d.transition=e("transition"),d.transitionDelay=e("transitionDelay"),d.transform=e("transform"),d.transformOrigin=e("transformOrigin"),d.filter=e("Filter"),d.transform3d=n();var h={transition:"transitionend",MozTransition:"transitionend",OTransition:"oTransitionEnd",WebkitTransition:"webkitTransitionEnd",msTransition:"MSTransitionEnd"},b=d.transitionEnd=h[d.transition]||null;for(var y in d)d.hasOwnProperty(y)&&"undefined"==typeof t.support[y]&&(t.support[y]=d[y]);return p=null,t.cssEase={_default:"ease","in":"ease-in",out:"ease-out","in-out":"ease-in-out",snap:"cubic-bezier(0,1,.5,1)",easeInCubic:"cubic-bezier(.550,.055,.675,.190)",easeOutCubic:"cubic-bezier(.215,.61,.355,1)",easeInOutCubic:"cubic-bezier(.645,.045,.355,1)",easeInCirc:"cubic-bezier(.6,.04,.98,.335)",easeOutCirc:"cubic-bezier(.075,.82,.165,1)",easeInOutCirc:"cubic-bezier(.785,.135,.15,.86)",easeInExpo:"cubic-bezier(.95,.05,.795,.035)",easeOutExpo:"cubic-bezier(.19,1,.22,1)",easeInOutExpo:"cubic-bezier(1,0,0,1)",easeInQuad:"cubic-bezier(.55,.085,.68,.53)",easeOutQuad:"cubic-bezier(.25,.46,.45,.94)",easeInOutQuad:"cubic-bezier(.455,.03,.515,.955)",easeInQuart:"cubic-bezier(.895,.03,.685,.22)",easeOutQuart:"cubic-bezier(.165,.84,.44,1)",easeInOutQuart:"cubic-bezier(.77,0,.175,1)",easeInQuint:"cubic-bezier(.755,.05,.855,.06)",easeOutQuint:"cubic-bezier(.23,1,.32,1)",easeInOutQuint:"cubic-bezier(.86,0,.07,1)",easeInSine:"cubic-bezier(.47,0,.745,.715)",easeOutSine:"cubic-bezier(.39,.575,.565,1)",easeInOutSine:"cubic-bezier(.445,.05,.55,.95)",easeInBack:"cubic-bezier(.6,-.28,.735,.045)",easeOutBack:"cubic-bezier(.175, .885,.32,1.275)",easeInOutBack:"cubic-bezier(.68,-.55,.265,1.55)"},t.cssHooks["transit:transform"]={get:function(e){return t(e).data("transform")||new i},set:function(e,n){var r=n;r instanceof i||(r=new i(r)),e.style[d.transform]="WebkitTransform"!==d.transform||l?r.toString():r.toString(!0),t(e).data("transform",r)}},t.cssHooks.transform={set:t.cssHooks["transit:transform"].set},t.cssHooks.filter={get:function(t){return t.style[d.filter]},set:function(t,e){t.style[d.filter]=e}},t.fn.jquery<"1.8"&&(t.cssHooks.transformOrigin={get:function(t){return t.style[d.transformOrigin]},set:function(t,e){t.style[d.transformOrigin]=e}},t.cssHooks.transition={get:function(t){return t.style[d.transition]},set:function(t,e){t.style[d.transition]=e}}),o("scale"),o("scaleX"),o("scaleY"),o("translate"),o("rotate"),o("rotateX"),o("rotateY"),o("rotate3d"),o("perspective"),o("skewX"),o("skewY"),o("x",!0),o("y",!0),i.prototype={setFromString:function(t,e){var n="string"==typeof e?e.split(","):e.constructor===Array?e:[e];n.unshift(t),i.prototype.set.apply(this,n)},set:function(t){var e=Array.prototype.slice.apply(arguments,[1]);this.setter[t]?this.setter[t].apply(this,e):this[t]=e.join(",")},get:function(t){return this.getter[t]?this.getter[t].apply(this):this[t]||0},setter:{rotate:function(t){this.rotate=c(t,"deg")},rotateX:function(t){this.rotateX=c(t,"deg")},rotateY:function(t){this.rotateY=c(t,"deg")},scale:function(t,e){void 0===e&&(e=t),this.scale=t+","+e},skewX:function(t){this.skewX=c(t,"deg")},skewY:function(t){this.skewY=c(t,"deg")},perspective:function(t){this.perspective=c(t,"px")},x:function(t){this.set("translate",t,null)},y:function(t){this.set("translate",null,t)},translate:function(t,e){void 0===this._translateX&&(this._translateX=0),void 0===this._translateY&&(this._translateY=0),null!==t&&void 0!==t&&(this._translateX=c(t,"px")),null!==e&&void 0!==e&&(this._translateY=c(e,"px")),this.translate=this._translateX+","+this._translateY}},getter:{x:function(){return this._translateX||0},y:function(){return this._translateY||0},scale:function(){var t=(this.scale||"1,1").split(",");return t[0]&&(t[0]=parseFloat(t[0])),t[1]&&(t[1]=parseFloat(t[1])),t[0]===t[1]?t[0]:t},rotate3d:function(){for(var t=(this.rotate3d||"0,0,0,0deg").split(","),e=0;3>=e;++e)t[e]&&(t[e]=parseFloat(t[e]));return t[3]&&(t[3]=c(t[3],"deg")),t}},parse:function(t){var e=this;t.replace(/([a-zA-Z0-9]+)\((.*?)\)/g,function(t,n,i){e.setFromString(n,i)})},toString:function(t){var e=[];for(var n in this)if(this.hasOwnProperty(n)){if(!d.transform3d&&("rotateX"===n||"rotateY"===n||"perspective"===n||"transformOrigin"===n))continue;"_"!==n[0]&&e.push(t&&"scale"===n?n+"3d("+this[n]+",1)":t&&"translate"===n?n+"3d("+this[n]+",0)":n+"("+this[n]+")")}return e.join(" ")}},t.fn.transition=t.fn.transit=function(e,n,i,s){var o=this,u=0,c=!0,p=t.extend(!0,{},e);"function"==typeof n&&(s=n,n=void 0),"object"==typeof n&&(i=n.easing,u=n.delay||0,c="undefined"==typeof n.queue?!0:n.queue,s=n.complete,n=n.duration),"function"==typeof i&&(s=i,i=void 0),"undefined"!=typeof p.easing&&(i=p.easing,delete p.easing),"undefined"!=typeof p.duration&&(n=p.duration,delete p.duration),"undefined"!=typeof p.complete&&(s=p.complete,delete p.complete),"undefined"!=typeof p.queue&&(c=p.queue,delete p.queue),"undefined"!=typeof p.delay&&(u=p.delay,delete p.delay),"undefined"==typeof n&&(n=t.fx.speeds._default),"undefined"==typeof i&&(i=t.cssEase._default),n=f(n);var l=a(p,n,i,u),h=t.transit.enabled&&d.transition,y=h?parseInt(n,10)+parseInt(u,10):0;if(0===y){var g=function(t){o.css(p),s&&s.apply(o),t&&t()};return r(o,c,g),o}var m={},v=function(e){var n=!1,i=function(){n&&o.unbind(b,i),y>0&&o.each(function(){this.style[d.transition]=m[this]||null}),"function"==typeof s&&s.apply(o),"function"==typeof e&&e()};y>0&&b&&t.transit.useTransitionEnd?(n=!0,o.bind(b,i)):window.setTimeout(i,y),o.each(function(){y>0&&(this.style[d.transition]=l),t(this).css(p)})},z=function(t){this.offsetWidth,v(t)};return r(o,c,z),this},t.transit.getTransitionValue=a,t});
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/meta/Space3DViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // Space3DViewer is an extension of a Viewer that implements the common visualization
4 | // framework for 3D stuff.
5 | // Space3DViewer implements drawing functionality, but does not implement any
6 | // message decoding functionality. Child classes that inherit from Space3DViewer
7 | // should decode a message and instruct the plotting framework what to do.
8 |
9 | class Space3DViewer extends Viewer {
10 | /**
11 | * Gets called when Viewer is first initialized.
12 | * @override
13 | **/
14 | onCreate() {
15 | // silly css nested div hell to force 100% width
16 | // but keep 1:1 aspect ratio
17 |
18 | this.wrapper = $('')
19 | .css({
20 | "position": "relative",
21 | "width": "100%",
22 | })
23 | .appendTo(this.card.content);
24 |
25 | this.wrapper2 = $('')
26 | .css({
27 | "width": "100%",
28 | "height": "0",
29 | "padding-bottom": "100%",
30 | "background": "#303035",
31 | "position": "relative",
32 | "overflow": "hidden",
33 | })
34 | .appendTo(this.wrapper);
35 |
36 | let that = this;
37 |
38 | this.gl = GL.create({ version:1, width: 500, height: 500});
39 | this.wrapper2[0].appendChild(this.gl.canvas);
40 | $(this.gl.canvas).css("width", "100%");
41 | this.gl.animate(); // launch loop
42 |
43 | this.cam_pos = [0,100,100];
44 | this.cam_theta = -1.5707;
45 | this.cam_phi = 1.0;
46 | this.cam_r = 50.0;
47 | this.cam_offset_x = 0.0;
48 | this.cam_offset_y = 0.0;
49 | this.cam_offset_z = 0.0;
50 |
51 | this.drawObjectsGl = null;
52 |
53 | //create basic matrices for cameras and transformation
54 | this.proj = mat4.create();
55 | this.view = mat4.create();
56 | this.model = mat4.create();
57 | this.mvp = mat4.create();
58 | this.temp = mat4.create();
59 |
60 | this.gl.captureMouse(true, true);
61 | this.gl.onmouse = function(e) {
62 | if(e.dragging) {
63 | if(e.rightButton) {
64 | that.cam_offset_x += e.deltax/30 * Math.sin(that.cam_theta);
65 | that.cam_offset_y -= e.deltax/30 * Math.cos(that.cam_theta);
66 | that.cam_offset_z += e.deltay/30;
67 | that.updatePerspective();
68 | } else {
69 | if(Math.abs(e.deltax) > 100 || Math.abs(e.deltay) > 100) return;
70 | that.cam_theta -= e.deltax / 300;
71 | that.cam_phi -= e.deltay / 300;
72 |
73 | // avoid euler singularities
74 | // also don't let the user flip the entire cloud around
75 | if(that.cam_phi < 0) {
76 | that.cam_phi = 0.001;
77 | }
78 | if(that.cam_phi > Math.PI) {
79 | that.cam_phi = Math.PI - 0.001;
80 | }
81 | that.updatePerspective();
82 | }
83 | }
84 | }
85 |
86 | this.gl.onmousewheel = function(e) {
87 | that.cam_r -= e.delta;
88 | if(that.cam_r < 1.0) that.cam_r = 1.0;
89 | if(that.cam_r > 1000.0) that.cam_r = 1000.0;
90 | that.updatePerspective();
91 | }
92 |
93 | this.updatePerspective = () => {
94 | that.cam_pos[0] = that.cam_offset_x + that.cam_r * Math.sin(that.cam_phi) * Math.cos(that.cam_theta);
95 | that.cam_pos[1] = that.cam_offset_y + that.cam_r * Math.sin(that.cam_phi) * Math.sin(that.cam_theta);
96 | that.cam_pos[2] = that.cam_offset_z + that.cam_r * Math.cos(that.cam_phi);
97 |
98 | that.view = mat4.create();
99 | mat4.perspective(that.proj, 45 * DEG2RAD, that.gl.canvas.width / that.gl.canvas.height, 0.1, 1000);
100 | mat4.lookAt(that.view, that.cam_pos, [this.cam_offset_x,this.cam_offset_y, this.cam_offset_z], [0,0,1]);
101 | mat4.multiply(that.mvp, that.proj, that.view);
102 | }
103 |
104 | this.updatePerspective();
105 |
106 | this.shader = new Shader('\
107 | precision highp float;\
108 | attribute vec3 a_vertex;\
109 | attribute vec4 a_color;\
110 | uniform mat4 u_mvp;\
111 | varying vec4 v_color;\
112 | void main() {\
113 | v_color = a_color;\
114 | gl_Position = u_mvp * vec4(a_vertex,1.0);\
115 | gl_PointSize = 1.5;\
116 | }\
117 | ', '\
118 | precision highp float;\
119 | uniform vec4 u_color;\
120 | varying vec4 v_color;\
121 | void main() {\
122 | gl_FragColor = u_color * v_color;\
123 | }\
124 | ');
125 | //generic gl flags and settings
126 | this.gl.clearColor(0.1,0.1,0.1,1);
127 | this.gl.disable( this.gl.DEPTH_TEST );
128 |
129 | //rendering loop
130 | this.gl.ondraw = function() {
131 | that.gl.clear( that.gl.COLOR_BUFFER_BIT | that.gl.DEPTH_BUFFER_BIT );
132 | if(!that.drawObjectsGl) return;
133 | for(let i in that.drawObjectsGl) {
134 | if(that.drawObjectsGl[i].type === "points") {
135 | that.shader.uniforms({
136 | u_color: [1,1,1,1],
137 | u_mvp: that.mvp
138 | }).draw(that.drawObjectsGl[i].mesh, gl.POINTS);
139 | } else if(that.drawObjectsGl[i].type === "lines") {
140 | that.shader.uniforms({
141 | u_color: [1,1,1,1],
142 | u_mvp: that.mvp
143 | }).draw(that.drawObjectsGl[i].mesh, gl.LINES);
144 | }
145 | }
146 | };
147 |
148 | // initialize static mesh for grid
149 |
150 | this.gridPoints = [];
151 | this.gridColors = [];
152 | for(let x=-5.0;x<=5.0+0.001;x+=1.0) {
153 | this.gridPoints.push(x);
154 | this.gridPoints.push(-5);
155 | this.gridPoints.push(0);
156 | this.gridPoints.push(x);
157 | this.gridPoints.push(5);
158 | this.gridPoints.push(0);
159 | for(let i=0;i<8;i++) {
160 | this.gridColors.push(1);
161 | }
162 | }
163 |
164 | for(let y=-5.0;y<=5.0+0.001;y+=1.0) {
165 | this.gridPoints.push(-5);
166 | this.gridPoints.push(y);
167 | this.gridPoints.push(0);
168 | this.gridPoints.push(5);
169 | this.gridPoints.push(y);
170 | this.gridPoints.push(0);
171 | for(let i=0;i<8;i++) {
172 | this.gridColors.push(1);
173 | }
174 | }
175 |
176 | this.gridMesh = GL.Mesh.load({vertices: this.gridPoints, colors: this.gridColors}, null, null, this.gl);
177 |
178 | // initialize static mesh for axes
179 |
180 | this.axesPoints = [ 0,0,0, 1,0,0, 0,0,0, 0,1,0, 0,0,0, 0,0,1, ];
181 | this.axesColors = [ 1,0,0,1, 1,0,0,1, 0,1,0,1, 0,1,0,1, 0,0.5,1,1, 0,0.5,1,1, ];
182 |
183 | this.axesMesh = GL.Mesh.load({vertices: this.axesPoints, colors: this.axesColors});
184 | }
185 |
186 | _getColor(v, vmin, vmax) {
187 | // cube edge walk from from http://paulbourke.net/miscellaneous/colourspace/
188 | let c = [1.0, 1.0, 1.0];
189 |
190 | if (v < vmin)
191 | v = vmin;
192 | if (v > vmax)
193 | v = vmax;
194 | let dv = vmax - vmin;
195 | if(dv < 1e-2) dv = 1e-2;
196 |
197 | if (v < (vmin + 0.25 * dv)) {
198 | c[0] = 0;
199 | c[1] = 4 * (v - vmin) / dv;
200 | } else if (v < (vmin + 0.5 * dv)) {
201 | c[0] = 0;
202 | c[2] = 1 + 4 * (vmin + 0.25 * dv - v) / dv;
203 | } else if (v < (vmin + 0.75 * dv)) {
204 | c[0] = 4 * (v - vmin - 0.5 * dv) / dv;
205 | c[2] = 0;
206 | } else {
207 | c[1] = 1 + 4 * (vmin + 0.75 * dv - v) / dv;
208 | c[2] = 0;
209 | }
210 |
211 | return(c);
212 | }
213 |
214 | draw(drawObjects) {
215 | this.drawObjects = drawObjects;
216 | let drawObjectsGl = [];
217 |
218 | // draw grid
219 |
220 | drawObjectsGl.push({type: "lines", mesh: this.gridMesh});
221 |
222 | // draw axes
223 |
224 | drawObjectsGl.push({type: "lines", mesh: this.axesMesh});
225 |
226 | for(let i in drawObjects) {
227 | let drawObject = drawObjects[i];
228 | if(drawObject.type === "points") {
229 | let colors = new Float32Array(drawObject.data.length / 3 * 4);
230 | let zmin = drawObject.zmin || -2;
231 | let zmax = drawObject.zmax || 2;
232 | let zrange = zmax - zmin;
233 | for(let j=0; j < drawObject.data.length / 3; j++) {
234 | let c = this._getColor(drawObject.data[3*j+2], zmin, zmax)
235 | colors[4*j] = c[0];
236 | colors[4*j+1] = c[1];
237 | colors[4*j+2] = c[2];
238 | colors[4*j+3] = 1;
239 | }
240 | let points = drawObject.data;
241 | drawObjectsGl.push({type: "points", mesh: GL.Mesh.load({vertices: points, colors: colors}, null, null, this.gl)});
242 | }
243 | }
244 | this.drawObjectsGl = drawObjectsGl;
245 | }
246 | }
247 |
248 | Space3DViewer.supportedTypes = [
249 | ];
250 |
251 | Space3DViewer.maxUpdateRate = 10.0;
252 |
253 | Viewer.registerViewer(Space3DViewer);
--------------------------------------------------------------------------------
/rosboard/handlers.py:
--------------------------------------------------------------------------------
1 | import json
2 | import socket
3 | import time
4 | import tornado
5 | import tornado.web
6 | import tornado.websocket
7 | import traceback
8 | import types
9 | import uuid
10 |
11 | from . import __version__
12 |
13 | class NoCacheStaticFileHandler(tornado.web.StaticFileHandler):
14 | def set_extra_headers(self, path):
15 | # Disable cache
16 | self.set_header('Cache-Control', 'no-store, no-cache, must-revalidate, max-age=0')
17 |
18 | class ROSBoardSocketHandler(tornado.websocket.WebSocketHandler):
19 | sockets = set()
20 |
21 | def initialize(self, node):
22 | # store the instance of the ROS node that created this WebSocketHandler so we can access it later
23 | self.node = node
24 |
25 | def get_compression_options(self):
26 | # Non-None enables compression with default options.
27 | return {}
28 |
29 | def open(self):
30 | self.id = uuid.uuid4() # unique socket id
31 | self.latency = 0 # latency measurement
32 | self.last_ping_times = [0] * 1024
33 | self.ping_seq = 0
34 |
35 | self.set_nodelay(True)
36 |
37 | # polyfill of is_closing() method for older versions of tornado
38 | if not hasattr(self.ws_connection, "is_closing"):
39 | self.ws_connection.is_closing = types.MethodType(
40 | lambda self_: self_.stream.closed() or self_.client_terminated or self_.server_terminated,
41 | self.ws_connection
42 | )
43 |
44 | self.update_intervals_by_topic = {} # this socket's throttle rate on each topic
45 | self.last_data_times_by_topic = {} # last time this socket received data on each topic
46 |
47 | ROSBoardSocketHandler.sockets.add(self)
48 |
49 | self.write_message(json.dumps([ROSBoardSocketHandler.MSG_SYSTEM, {
50 | "hostname": self.node.title,
51 | "version": __version__,
52 | }], separators=(',', ':')))
53 |
54 | def on_close(self):
55 | ROSBoardSocketHandler.sockets.remove(self)
56 |
57 | # when socket closes, remove ourselves from all subscriptions
58 | for topic_name in self.node.remote_subs:
59 | if self.id in self.node.remote_subs[topic_name]:
60 | self.node.remote_subs[topic_name].remove(self.id)
61 |
62 | @classmethod
63 | def send_pings(cls):
64 | """
65 | Send pings to all sockets. When pongs are received they will be used for measuring
66 | latency and clock differences.
67 | """
68 |
69 | for socket in cls.sockets:
70 | try:
71 | socket.last_ping_times[socket.ping_seq % 1024] = time.time() * 1000
72 | if socket.ws_connection and not socket.ws_connection.is_closing():
73 | socket.write_message(json.dumps([ROSBoardSocketHandler.MSG_PING, {
74 | ROSBoardSocketHandler.PING_SEQ: socket.ping_seq,
75 | }], separators=(',', ':')))
76 | socket.ping_seq += 1
77 | except Exception as e:
78 | print("Error sending message: %s" % str(e))
79 |
80 | @classmethod
81 | def broadcast(cls, message):
82 | """
83 | Broadcasts a dict-ified ROS message (message) to all sockets that care about that topic.
84 | The dict message should contain metadata about what topic it was
85 | being sent on: message["_topic_name"], message["_topic_type"].
86 | """
87 |
88 | try:
89 | if message[0] == ROSBoardSocketHandler.MSG_TOPICS:
90 | json_msg = json.dumps(message, separators=(',', ':'))
91 | for socket in cls.sockets:
92 | if socket.ws_connection and not socket.ws_connection.is_closing():
93 | socket.write_message(json_msg)
94 | elif message[0] == ROSBoardSocketHandler.MSG_MSG:
95 | topic_name = message[1]["_topic_name"]
96 | json_msg = None
97 | for socket in cls.sockets:
98 | if topic_name not in socket.node.remote_subs:
99 | continue
100 | if socket.id not in socket.node.remote_subs[topic_name]:
101 | continue
102 | t = time.time()
103 | if t - socket.last_data_times_by_topic.get(topic_name, 0.0) < \
104 | socket.update_intervals_by_topic.get(topic_name) - 2e-4:
105 | continue
106 | if socket.ws_connection and not socket.ws_connection.is_closing():
107 | if json_msg is None:
108 | json_msg = json.dumps(message, separators=(',', ':'))
109 | socket.write_message(json_msg)
110 | socket.last_data_times_by_topic[topic_name] = t
111 | except Exception as e:
112 | print("Error sending message: %s" % str(e))
113 | traceback.print_exc()
114 |
115 | def on_message(self, message):
116 | """
117 | Message received from the client.
118 | """
119 |
120 | if self.ws_connection.is_closing():
121 | return
122 |
123 | # JSON decode it, give up if it isn't valid JSON
124 | try:
125 | argv = json.loads(message)
126 | except (ValueError, TypeError):
127 | print("error: bad: %s" % message)
128 | return
129 |
130 | # make sure the received argv is a list and the first element is a string and indicates the type of command
131 | if type(argv) is not list or len(argv) < 1 or type(argv[0]) is not str:
132 | print("error: bad: %s" % message)
133 | return
134 |
135 | # if we got a pong for our own ping, compute latency and clock difference
136 | elif argv[0] == ROSBoardSocketHandler.MSG_PONG:
137 | if len(argv) != 2 or type(argv[1]) is not dict:
138 | print("error: pong: bad: %s" % message)
139 | return
140 |
141 | received_pong_time = time.time() * 1000
142 | self.latency = (received_pong_time - self.last_ping_times[argv[1].get(ROSBoardSocketHandler.PONG_SEQ, 0) % 1024]) / 2
143 | if self.latency > 1000.0:
144 | self.node.logwarn("socket %s has high latency of %.2f ms" % (str(self.id), self.latency))
145 |
146 | if self.latency > 10000.0:
147 | self.node.logerr("socket %s has excessive latency of %.2f ms; closing connection" % (str(self.id), self.latency))
148 | self.close()
149 |
150 | # client wants to subscribe to topic
151 | elif argv[0] == ROSBoardSocketHandler.MSG_SUB:
152 | if len(argv) != 2 or type(argv[1]) is not dict:
153 | print("error: sub: bad: %s" % message)
154 | return
155 |
156 | topic_name = argv[1].get("topicName")
157 | max_update_rate = float(argv[1].get("maxUpdateRate", 24.0))
158 |
159 | self.update_intervals_by_topic[topic_name] = 1.0 / max_update_rate
160 | self.node.update_intervals_by_topic[topic_name] = min(
161 | self.node.update_intervals_by_topic.get(topic_name, 1.),
162 | self.update_intervals_by_topic[topic_name]
163 | )
164 |
165 | if topic_name is None:
166 | print("error: no topic specified")
167 | return
168 |
169 | if topic_name not in self.node.remote_subs:
170 | self.node.remote_subs[topic_name] = set()
171 |
172 | self.node.remote_subs[topic_name].add(self.id)
173 | self.node.sync_subs()
174 |
175 | # client wants to unsubscribe from topic
176 | elif argv[0] == ROSBoardSocketHandler.MSG_UNSUB:
177 | if len(argv) != 2 or type(argv[1]) is not dict:
178 | print("error: unsub: bad: %s" % message)
179 | return
180 | topic_name = argv[1].get("topicName")
181 |
182 | if topic_name not in self.node.remote_subs:
183 | self.node.remote_subs[topic_name] = set()
184 |
185 | try:
186 | self.node.remote_subs[topic_name].remove(self.id)
187 | except KeyError:
188 | print("KeyError trying to remove sub")
189 |
190 | ROSBoardSocketHandler.MSG_PING = "p";
191 | ROSBoardSocketHandler.MSG_PONG = "q";
192 | ROSBoardSocketHandler.MSG_MSG = "m";
193 | ROSBoardSocketHandler.MSG_TOPICS = "t";
194 | ROSBoardSocketHandler.MSG_SUB = "s";
195 | ROSBoardSocketHandler.MSG_SYSTEM = "y";
196 | ROSBoardSocketHandler.MSG_UNSUB = "u";
197 |
198 | ROSBoardSocketHandler.PING_SEQ = "s";
199 | ROSBoardSocketHandler.PONG_SEQ = "s";
200 | ROSBoardSocketHandler.PONG_TIME = "t";
201 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/meta/Viewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // Viewer is just a base class. It just has the boilerplate code to
4 | // instantiate the elemnets (title, content, close button, spinner) of a card
5 | // and display an error if there is an error. Viewer doesn't have any visualization
6 | // capability at all, hence, it has no supportedTypes. Child classes will inherit
7 | // from Viewer and implement visualization functionality.
8 |
9 | class Viewer {
10 | /**
11 | * Class constructor.
12 | * @constructor
13 | **/
14 | constructor(card, topicName, topicType) {
15 | this.card = card;
16 | this.isPaused = false;
17 |
18 | this.topicName = topicName;
19 | this.topicType = topicType;
20 |
21 | this.onClose = () => {};
22 | let that = this;
23 |
24 | // div container at the top right for all the buttons
25 | card.buttons = $('').addClass('card-buttons').text('').appendTo(card);
26 |
27 | // card title div
28 | card.title = $('').addClass('card-title').text("Waiting for data ...").appendTo(card);
29 |
30 | // card content div
31 | card.content = $('').addClass('card-content').text('').appendTo(card);
32 |
33 | // card pause button
34 | let menuId = 'menu-' + Math.floor(Math.random() * 1e6);
35 |
36 | card.settingsButton = $('')
37 | .addClass('mdl-button')
38 | .addClass('mdl-js-button')
39 | .addClass('mdl-button--icon')
40 | .addClass('mdl-button--colored')
41 | .append($('').addClass('material-icons').text('more_vert'))
42 | .appendTo(card.buttons);
43 | /*card.settingsButton.click(function(e) {
44 | console.log("not implemented yet");
45 | });*/
46 |
47 | card.menu = $('').appendTo(card);
49 |
50 | // \
51 | // \
52 | // \
53 | // \
54 |
55 | let viewers = Viewer.getViewersForType(this.topicType);
56 | for(let i in viewers) {
57 | let item = $('').appendTo(this.card.menu);
58 | let that = this;
59 | item.click(() => { Viewer.onSwitchViewer(that, viewers[i]); });
60 | }
61 |
62 | componentHandler.upgradeAllRegistered();
63 |
64 | // card pause button
65 | card.pauseButton = $('')
66 | .addClass('mdl-button')
67 | .addClass('mdl-js-button')
68 | .addClass('mdl-button--icon')
69 | .addClass('mdl-button--colored')
70 | .append($('').addClass('material-icons').text('pause'))
71 | .appendTo(card.buttons);
72 | card.pauseButton.click(function(e) {
73 | that.isPaused = !that.isPaused;
74 | that.card.pauseButton.find('i').text(that.isPaused ? 'play_arrow' : 'pause');
75 | });
76 |
77 | // card close button
78 | card.closeButton = $('')
79 | .addClass('mdl-button')
80 | .addClass('mdl-js-button')
81 | .addClass('mdl-button--icon')
82 | .append($('').addClass('material-icons').text('close'))
83 | .appendTo(card.buttons);
84 | card.closeButton.click(() => { Viewer.onClose(that); });
85 |
86 | // call onCreate(); child class will override this and initialize its UI
87 | this.onCreate();
88 |
89 | // lay a spinner over everything and get rid of it after first data is received
90 | this.loaderContainer = $('')
91 | .addClass('loader-container')
92 | .append($('').addClass('loader'))
93 | .appendTo(this.card);
94 |
95 | this.lastDataTime = 0.0;
96 | }
97 |
98 | /**
99 | * Gets called when Viewer is first initialized.
100 | * @override
101 | **/
102 | onCreate() {
103 | // for MDL elements to get instantiated
104 | if(!(typeof(componentHandler) === 'undefined')){
105 | componentHandler.upgradeAllRegistered();
106 | }
107 | }
108 | destroy() {
109 | this.card.empty();
110 | }
111 |
112 | onResize() { }
113 |
114 | onDataPaused(data) { }
115 |
116 | onData(data) { }
117 |
118 | update(data) {
119 | let time = Date.now();
120 | if( (time - this.lastDataTime)/1000.0 < 1/this.constructor.maxUpdateRate - 5e-4) {
121 | return;
122 | }
123 |
124 | if(this.isPaused) { this.onDataPaused(data); return; }
125 |
126 | this.lastDataTime = time;
127 |
128 | // get rid of the spinner
129 | if(this.loaderContainer) {
130 | this.loaderContainer.remove();
131 | this.loaderContainer = null;
132 | }
133 |
134 | if(data._error) {
135 | this.error(data._error);
136 | return;
137 | }
138 |
139 | if(data._warn) {
140 | this.warn(data._warn);
141 | }
142 |
143 | // actually update the data
144 | this.onData(data);
145 | }
146 |
147 | error(error_text) {
148 | if(!this.card.error) {
149 | this.card.error = $("").css({
150 | "background": "#f06060",
151 | "color": "#ffffff",
152 | "padding": "20pt",
153 | }).appendTo(this.card);
154 | }
155 | this.card.error.text(error_text).css({
156 | "display": "",
157 | });
158 | this.card.content.css({
159 | "display": "none",
160 | })
161 | }
162 |
163 | warn(warn_text) {
164 | if(!this.card.warn) {
165 | this.card.warn = $("").css({
166 | "background": "#a08000",
167 | "color": "#ffffff",
168 | "padding": "20pt",
169 | }).appendTo(this.card);
170 | }
171 | this.card.warn.text(warn_text).css({
172 | "display": "",
173 | });
174 | }
175 |
176 | tip(tip_text) {
177 | if(this.tipHideTimeout) clearTimeout(this.tipHideTimeout);
178 | if(!this.tipBox) {
179 | this.tipBox = $("").css({
180 | "background": "rgba(0,0,0,0.3)",
181 | "position": "absolute",
182 | "z-index": "10",
183 | "bottom": "0",
184 | "width": "calc( 100% - 24pt )",
185 | "height": "24px",
186 | "text-overflow": "ellipsis",
187 | "overflow": "hidden",
188 | "padding-left": "12pt",
189 | "padding-right": "12pt",
190 | "padding-bottom": "4pt",
191 | "padding-top": "4pt",
192 | "font-size": "8pt",
193 | "white-space": "nowrap",
194 | "color": "#ffffff",
195 | }).addClass("monospace").appendTo(this.card);
196 | }
197 | let that = this;
198 | this.tipBox.css({"display": ""});
199 | this.tipHideTimeout = setTimeout(() => that.tipBox.css({"display": "none"}), 1000);
200 | this.tipBox.text(tip_text);
201 | }
202 | }
203 |
204 | Viewer.friendlyName = "Viewer";
205 |
206 | // can be overridden by child class
207 | // list of supported message types by viewer, or "*" for all types
208 | // todo: support regexes?
209 | Viewer.supportedTypes = [];
210 |
211 | // can be overridden by child class
212 | // max update rate that this viewer can handle
213 | // for some viewers that do extensive DOM manipulations, this should be set conservatively
214 | Viewer.maxUpdateRate = 50.0;
215 |
216 | // not to be overwritten by child class!
217 | // stores registered viewers in sequence of loading
218 | Viewer._viewers = [];
219 |
220 | // override this
221 | Viewer.onClose = (viewerInstance) => { console.log("not implemented; override necessary"); }
222 | Viewer.onSwitchViewer = (viewerInstance, newViewerType) => { console.log("not implemented; override necessary"); }
223 |
224 | // not to be overwritten by child class!
225 | Viewer.registerViewer = (viewer) => {
226 | // registers a viewer. the viewer child class calls this at the end of the file to register itself
227 | Viewer._viewers.push(viewer);
228 | };
229 |
230 | // not to be overwritten by child class!
231 | Viewer.getDefaultViewerForType = (type) => {
232 | // gets the viewer class for a given message type (e.g. "std_msgs/msg/String")
233 |
234 | // if type is "package/MessageType", converted it to "package/msgs/MessageType"
235 | let tokens = type.split("/");
236 | if(tokens.length == 2) {
237 | type = [tokens[0], "msg", tokens[1]].join("/");
238 | }
239 |
240 | // go down the list of registered viewers and return the first match
241 | for(let i in Viewer._viewers) {
242 | if(Viewer._viewers[i].supportedTypes.includes(type)) {
243 | return Viewer._viewers[i];
244 | }
245 | if(Viewer._viewers[i].supportedTypes.includes("*")) {
246 | return Viewer._viewers[i];
247 | }
248 | }
249 | return null;
250 | }
251 |
252 | // not to be overwritten by child class!
253 | Viewer.getViewersForType = (type) => {
254 | // gets the viewer classes for a given message type (e.g. "std_msgs/msg/String")
255 |
256 | let matchingViewers = [];
257 |
258 | // if type is "package/MessageType", converted it to "package/msgs/MessageType"
259 | let tokens = type.split("/");
260 | if(tokens.length == 2) {
261 | type = [tokens[0], "msg", tokens[1]].join("/");
262 | }
263 |
264 | // go down the list of registered viewers and return the first match
265 | for(let i in Viewer._viewers) {
266 | if(Viewer._viewers[i].supportedTypes.includes(type)) {
267 | matchingViewers.push(Viewer._viewers[i]);
268 | }
269 | if(Viewer._viewers[i].supportedTypes.includes("*")) {
270 | matchingViewers.push(Viewer._viewers[i]);
271 | }
272 | }
273 |
274 | return matchingViewers;
275 | }
276 |
277 |
--------------------------------------------------------------------------------
/rosboard/html/js/index.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | importJsOnce("js/viewers/meta/Viewer.js");
4 | importJsOnce("js/viewers/meta/Space2DViewer.js");
5 | importJsOnce("js/viewers/meta/Space3DViewer.js");
6 |
7 | importJsOnce("js/viewers/ImageViewer.js");
8 | importJsOnce("js/viewers/LogViewer.js");
9 | importJsOnce("js/viewers/ProcessListViewer.js");
10 | importJsOnce("js/viewers/MapViewer.js");
11 | importJsOnce("js/viewers/LaserScanViewer.js");
12 | importJsOnce("js/viewers/GeometryViewer.js");
13 | importJsOnce("js/viewers/PolygonViewer.js");
14 | importJsOnce("js/viewers/DiagnosticViewer.js");
15 | importJsOnce("js/viewers/TimeSeriesPlotViewer.js");
16 | importJsOnce("js/viewers/PointCloud2Viewer.js");
17 |
18 | // GenericViewer must be last
19 | importJsOnce("js/viewers/GenericViewer.js");
20 |
21 | importJsOnce("js/transports/WebSocketV1Transport.js");
22 |
23 | var snackbarContainer = document.querySelector('#demo-toast-example');
24 |
25 | let subscriptions = {};
26 |
27 | if(window.localStorage && window.localStorage.subscriptions) {
28 | if(window.location.search && window.location.search.indexOf("reset") !== -1) {
29 | subscriptions = {};
30 | updateStoredSubscriptions();
31 | window.location.href = "?";
32 | } else {
33 | try {
34 | subscriptions = JSON.parse(window.localStorage.subscriptions);
35 | } catch(e) {
36 | console.log(e);
37 | subscriptions = {};
38 | }
39 | }
40 | }
41 |
42 | let $grid = null;
43 | $(() => {
44 | $grid = $('.grid').masonry({
45 | itemSelector: '.card',
46 | gutter: 10,
47 | percentPosition: true,
48 | });
49 | $grid.masonry("layout");
50 | });
51 |
52 | setInterval(() => {
53 | if(currentTransport && !currentTransport.isConnected()) {
54 | console.log("attempting to reconnect ...");
55 | currentTransport.connect();
56 | }
57 | }, 5000);
58 |
59 | function updateStoredSubscriptions() {
60 | if(window.localStorage) {
61 | let storedSubscriptions = {};
62 | for(let topicName in subscriptions) {
63 | storedSubscriptions[topicName] = {
64 | topicType: subscriptions[topicName].topicType,
65 | };
66 | }
67 | window.localStorage['subscriptions'] = JSON.stringify(storedSubscriptions);
68 | }
69 | }
70 |
71 | function newCard() {
72 | // creates a new card, adds it to the grid, and returns it.
73 | let card = $("").addClass('card')
74 | .appendTo($('.grid'));
75 | return card;
76 | }
77 |
78 | let onOpen = function() {
79 | for(let topic_name in subscriptions) {
80 | console.log("Re-subscribing to " + topic_name);
81 | initSubscribe({topicName: topic_name, topicType: subscriptions[topic_name].topicType});
82 | }
83 | }
84 |
85 | let onSystem = function(system) {
86 | if(system.hostname) {
87 | console.log("hostname: " + system.hostname);
88 | $('.mdl-layout-title').text("ROSboard: " + system.hostname);
89 | }
90 |
91 | if(system.version) {
92 | console.log("server version: " + system.version);
93 | versionCheck(system.version);
94 | }
95 | }
96 |
97 | let onMsg = function(msg) {
98 | if(!subscriptions[msg._topic_name]) {
99 | console.log("Received unsolicited message", msg);
100 | } else if(!subscriptions[msg._topic_name].viewer) {
101 | console.log("Received msg but no viewer", msg);
102 | } else {
103 | subscriptions[msg._topic_name].viewer.update(msg);
104 | }
105 | }
106 |
107 | let currentTopics = {};
108 | let currentTopicsStr = "";
109 |
110 | let onTopics = function(topics) {
111 |
112 | // check if topics has actually changed, if not, don't do anything
113 | // lazy shortcut to deep compares, might possibly even be faster than
114 | // implementing a deep compare due to
115 | // native optimization of JSON.stringify
116 | let newTopicsStr = JSON.stringify(topics);
117 | if(newTopicsStr === currentTopicsStr) return;
118 | currentTopics = topics;
119 | currentTopicsStr = newTopicsStr;
120 |
121 | let topicTree = treeifyPaths(Object.keys(topics));
122 |
123 | $("#topics-nav-ros").empty();
124 | $("#topics-nav-system").empty();
125 |
126 | addTopicTreeToNav(topicTree[0], $('#topics-nav-ros'));
127 |
128 | $('')
129 | .addClass("mdl-navigation__link")
130 | .click(() => { initSubscribe({topicName: "_dmesg", topicType: "rcl_interfaces/msg/Log"}); })
131 | .text("dmesg")
132 | .appendTo($("#topics-nav-system"));
133 |
134 | $('')
135 | .addClass("mdl-navigation__link")
136 | .click(() => { initSubscribe({topicName: "_top", topicType: "rosboard_msgs/msg/ProcessList"}); })
137 | .text("Processes")
138 | .appendTo($("#topics-nav-system"));
139 |
140 | $('')
141 | .addClass("mdl-navigation__link")
142 | .click(() => { initSubscribe({topicName: "_system_stats", topicType: "rosboard_msgs/msg/SystemStats"}); })
143 | .text("System stats")
144 | .appendTo($("#topics-nav-system"));
145 | }
146 |
147 | function addTopicTreeToNav(topicTree, el, level = 0, path = "") {
148 | topicTree.children.sort((a, b) => {
149 | if(a.name>b.name) return 1;
150 | if(a.name {
154 | let subEl = $('')
155 | .css(level < 1 ? {} : {
156 | "padding-left": "0pt",
157 | "margin-left": "12pt",
158 | "border-left": "1px dashed #808080",
159 | })
160 | .appendTo(el);
161 | let fullTopicName = path + "/" + subTree.name;
162 | let topicType = currentTopics[fullTopicName];
163 | if(topicType) {
164 | $('')
165 | .addClass("mdl-navigation__link")
166 | .css({
167 | "padding-left": "12pt",
168 | "margin-left": 0,
169 | })
170 | .click(() => { initSubscribe({topicName: fullTopicName, topicType: topicType}); })
171 | .text(subTree.name)
172 | .appendTo(subEl);
173 | } else {
174 | $('')
175 | .addClass("mdl-navigation__link")
176 | .attr("disabled", "disabled")
177 | .css({
178 | "padding-left": "12pt",
179 | "margin-left": 0,
180 | opacity: 0.5,
181 | })
182 | .text(subTree.name)
183 | .appendTo(subEl);
184 | }
185 | addTopicTreeToNav(subTree, subEl, level + 1, path + "/" + subTree.name);
186 | });
187 | }
188 |
189 | function initSubscribe({topicName, topicType}) {
190 | // creates a subscriber for topicName
191 | // and also initializes a viewer (if it doesn't already exist)
192 | // in advance of arrival of the first data
193 | // this way the user gets a snappy UI response because the viewer appears immediately
194 | if(!subscriptions[topicName]) {
195 | subscriptions[topicName] = {
196 | topicType: topicType,
197 | }
198 | }
199 | currentTransport.subscribe({topicName: topicName});
200 | if(!subscriptions[topicName].viewer) {
201 | let card = newCard();
202 | let viewer = Viewer.getDefaultViewerForType(topicType);
203 | try {
204 | subscriptions[topicName].viewer = new viewer(card, topicName, topicType);
205 | } catch(e) {
206 | console.log(e);
207 | card.remove();
208 | }
209 | $grid.masonry("appended", card);
210 | $grid.masonry("layout");
211 | }
212 | updateStoredSubscriptions();
213 | }
214 |
215 | let currentTransport = null;
216 |
217 | function initDefaultTransport() {
218 | currentTransport = new WebSocketV1Transport({
219 | path: "/rosboard/v1",
220 | onOpen: onOpen,
221 | onMsg: onMsg,
222 | onTopics: onTopics,
223 | onSystem: onSystem,
224 | });
225 | currentTransport.connect();
226 | }
227 |
228 | function treeifyPaths(paths) {
229 | // turn a bunch of ros topics into a tree
230 | let result = [];
231 | let level = {result};
232 |
233 | paths.forEach(path => {
234 | path.split('/').reduce((r, name, i, a) => {
235 | if(!r[name]) {
236 | r[name] = {result: []};
237 | r.result.push({name, children: r[name].result})
238 | }
239 |
240 | return r[name];
241 | }, level)
242 | });
243 | return result;
244 | }
245 |
246 | let lastBotherTime = 0.0;
247 | function versionCheck(currentVersionText) {
248 | $.get("https://raw.githubusercontent.com/dheera/rosboard/release/setup.py").done((data) => {
249 | let matches = data.match(/version='(.*)'/);
250 | if(matches.length < 2) return;
251 | let latestVersion = matches[1].split(".").map(num => parseInt(num, 10));
252 | let currentVersion = currentVersionText.split(".").map(num => parseInt(num, 10));
253 | let latestVersionInt = latestVersion[0] * 1000000 + latestVersion[1] * 1000 + latestVersion[2];
254 | let currentVersionInt = currentVersion[0] * 1000000 + currentVersion[1] * 1000 + currentVersion[2];
255 | if(currentVersion < latestVersion && Date.now() - lastBotherTime > 1800000) {
256 | lastBotherTime = Date.now();
257 | snackbarContainer.MaterialSnackbar.showSnackbar({
258 | message: "New version of ROSboard available (" + currentVersionText + " -> " + matches[1] + ").",
259 | actionText: "Check it out",
260 | actionHandler: ()=> {window.location.href="https://github.com/dheera/rosboard/"},
261 | });
262 | }
263 | });
264 | }
265 |
266 | $(() => {
267 | if(window.location.href.indexOf("rosboard.com") === -1) {
268 | initDefaultTransport();
269 | }
270 | });
271 |
272 | Viewer.onClose = function(viewerInstance) {
273 | let topicName = viewerInstance.topicName;
274 | let topicType = viewerInstance.topicType;
275 | currentTransport.unsubscribe({topicName:topicName});
276 | $grid.masonry("remove", viewerInstance.card);
277 | $grid.masonry("layout");
278 | delete(subscriptions[topicName].viewer);
279 | delete(subscriptions[topicName]);
280 | updateStoredSubscriptions();
281 | }
282 |
283 | Viewer.onSwitchViewer = (viewerInstance, newViewerType) => {
284 | let topicName = viewerInstance.topicName;
285 | let topicType = viewerInstance.topicType;
286 | if(!subscriptions[topicName].viewer === viewerInstance) console.error("viewerInstance does not match subscribed instance");
287 | let card = subscriptions[topicName].viewer.card;
288 | subscriptions[topicName].viewer.destroy();
289 | delete(subscriptions[topicName].viewer);
290 | subscriptions[topicName].viewer = new newViewerType(card, topicName, topicType);
291 | };
292 |
--------------------------------------------------------------------------------
/rosboard/html/js/leaflet.easy-button.js:
--------------------------------------------------------------------------------
1 | (function(){
2 |
3 | // This is for grouping buttons into a bar
4 | // takes an array of `L.easyButton`s and
5 | // then the usual `.addTo(map)`
6 | L.Control.EasyBar = L.Control.extend({
7 |
8 | options: {
9 | position: 'topleft', // part of leaflet's defaults
10 | id: null, // an id to tag the Bar with
11 | leafletClasses: true // use leaflet classes?
12 | },
13 |
14 |
15 | initialize: function(buttons, options){
16 |
17 | if(options){
18 | L.Util.setOptions( this, options );
19 | }
20 |
21 | this._buildContainer();
22 | this._buttons = [];
23 |
24 | for(var i = 0; i < buttons.length; i++){
25 | buttons[i]._bar = this;
26 | buttons[i]._container = buttons[i].button;
27 | this._buttons.push(buttons[i]);
28 | this.container.appendChild(buttons[i].button);
29 | }
30 |
31 | },
32 |
33 |
34 | _buildContainer: function(){
35 | this._container = this.container = L.DomUtil.create('div', '');
36 | this.options.leafletClasses && L.DomUtil.addClass(this.container, 'leaflet-bar easy-button-container leaflet-control');
37 | this.options.id && (this.container.id = this.options.id);
38 | },
39 |
40 |
41 | enable: function(){
42 | L.DomUtil.addClass(this.container, 'enabled');
43 | L.DomUtil.removeClass(this.container, 'disabled');
44 | this.container.setAttribute('aria-hidden', 'false');
45 | return this;
46 | },
47 |
48 |
49 | disable: function(){
50 | L.DomUtil.addClass(this.container, 'disabled');
51 | L.DomUtil.removeClass(this.container, 'enabled');
52 | this.container.setAttribute('aria-hidden', 'true');
53 | return this;
54 | },
55 |
56 |
57 | onAdd: function () {
58 | return this.container;
59 | },
60 |
61 | addTo: function (map) {
62 | this._map = map;
63 |
64 | for(var i = 0; i < this._buttons.length; i++){
65 | this._buttons[i]._map = map;
66 | }
67 |
68 | var container = this._container = this.onAdd(map),
69 | pos = this.getPosition(),
70 | corner = map._controlCorners[pos];
71 |
72 | L.DomUtil.addClass(container, 'leaflet-control');
73 |
74 | if (pos.indexOf('bottom') !== -1) {
75 | corner.insertBefore(container, corner.firstChild);
76 | } else {
77 | corner.appendChild(container);
78 | }
79 |
80 | return this;
81 | }
82 |
83 | });
84 |
85 | L.easyBar = function(){
86 | var args = [L.Control.EasyBar];
87 | for(var i = 0; i < arguments.length; i++){
88 | args.push( arguments[i] );
89 | }
90 | return new (Function.prototype.bind.apply(L.Control.EasyBar, args));
91 | };
92 |
93 | // L.EasyButton is the actual buttons
94 | // can be called without being grouped into a bar
95 | L.Control.EasyButton = L.Control.extend({
96 |
97 | options: {
98 | position: 'topleft', // part of leaflet's defaults
99 |
100 | id: null, // an id to tag the button with
101 |
102 | type: 'replace', // [(replace|animate)]
103 | // replace swaps out elements
104 | // animate changes classes with all elements inserted
105 |
106 | states: [], // state names look like this
107 | // {
108 | // stateName: 'untracked',
109 | // onClick: function(){ handle_nav_manually(); };
110 | // title: 'click to make inactive',
111 | // icon: 'fa-circle', // wrapped with
112 | // }
113 |
114 | leafletClasses: true, // use leaflet styles for the button
115 | tagName: 'button',
116 | },
117 |
118 |
119 |
120 | initialize: function(icon, onClick, title, id){
121 |
122 | // clear the states manually
123 | this.options.states = [];
124 |
125 | // add id to options
126 | if(id != null){
127 | this.options.id = id;
128 | }
129 |
130 | // storage between state functions
131 | this.storage = {};
132 |
133 | // is the last item an object?
134 | if( typeof arguments[arguments.length-1] === 'object' ){
135 |
136 | // if so, it should be the options
137 | L.Util.setOptions( this, arguments[arguments.length-1] );
138 | }
139 |
140 | // if there aren't any states in options
141 | // use the early params
142 | if( this.options.states.length === 0 &&
143 | typeof icon === 'string' &&
144 | typeof onClick === 'function'){
145 |
146 | // turn the options object into a state
147 | this.options.states.push({
148 | icon: icon,
149 | onClick: onClick,
150 | title: typeof title === 'string' ? title : ''
151 | });
152 | }
153 |
154 | // curate and move user's states into
155 | // the _states for internal use
156 | this._states = [];
157 |
158 | for(var i = 0; i < this.options.states.length; i++){
159 | this._states.push( new State(this.options.states[i], this) );
160 | }
161 |
162 | this._buildButton();
163 |
164 | this._activateState(this._states[0]);
165 |
166 | },
167 |
168 | _buildButton: function(){
169 |
170 | this.button = L.DomUtil.create(this.options.tagName, '');
171 |
172 | if (this.options.tagName === 'button') {
173 | this.button.setAttribute('type', 'button');
174 | }
175 |
176 | if (this.options.id ){
177 | this.button.id = this.options.id;
178 | }
179 |
180 | if (this.options.leafletClasses){
181 | L.DomUtil.addClass(this.button, 'easy-button-button leaflet-bar-part leaflet-interactive');
182 | }
183 |
184 | // don't let double clicks and mousedown get to the map
185 | L.DomEvent.addListener(this.button, 'dblclick', L.DomEvent.stop);
186 | L.DomEvent.addListener(this.button, 'mousedown', L.DomEvent.stop);
187 |
188 | // take care of normal clicks
189 | L.DomEvent.addListener(this.button,'click', function(e){
190 | L.DomEvent.stop(e);
191 | this._currentState.onClick(this, this._map ? this._map : null );
192 | this._map && this._map.getContainer().focus();
193 | }, this);
194 |
195 | // prep the contents of the control
196 | if(this.options.type == 'replace'){
197 | this.button.appendChild(this._currentState.icon);
198 | } else {
199 | for(var i=0;i"']/) ){
344 |
345 | // if so, the user should have put in html
346 | // so move forward as such
347 | tmpIcon = ambiguousIconString;
348 |
349 | // then it wasn't html, so
350 | // it's a class list, figure out what kind
351 | } else {
352 | ambiguousIconString = ambiguousIconString.replace(/(^\s*|\s*$)/g,'');
353 | tmpIcon = L.DomUtil.create('span', '');
354 |
355 | if( ambiguousIconString.indexOf('fa-') === 0 ){
356 | L.DomUtil.addClass(tmpIcon, 'fa ' + ambiguousIconString)
357 | } else if ( ambiguousIconString.indexOf('glyphicon-') === 0 ) {
358 | L.DomUtil.addClass(tmpIcon, 'glyphicon ' + ambiguousIconString)
359 | } else {
360 | L.DomUtil.addClass(tmpIcon, /*rollwithit*/ ambiguousIconString)
361 | }
362 |
363 | // make this a string so that it's easy to set innerHTML below
364 | tmpIcon = tmpIcon.outerHTML;
365 | }
366 |
367 | return tmpIcon;
368 | }
369 |
370 | })();
371 |
--------------------------------------------------------------------------------
/rosboard/html/js/viewers/meta/Space2DViewer.js:
--------------------------------------------------------------------------------
1 | "use strict";
2 |
3 | // Space2DViewer is an extension of a Viewer that implements the common visualization
4 | // framework for 2D plots, e.g. paths, points in a 2D space.
5 | // Space2DViewer implements drawing functionality, but does not implement any
6 | // message decoding functionality. Child classes that inherit from Space2DViewer
7 | // should decode a message and instruct the plotting framework what to do.
8 |
9 | class Space2DViewer extends Viewer {
10 | /**
11 | * Gets called when Viewer is first initialized.
12 | * @override
13 | **/
14 | onCreate() {
15 | // silly css nested div hell to force 100% width
16 | // but keep 1:1 aspect ratio
17 |
18 | this.wrapper = $('')
19 | .css({
20 | "position": "relative",
21 | "width": "100%",
22 | })
23 | .appendTo(this.card.content);
24 |
25 | this.wrapper2 = $('')
26 | .css({
27 | "width": "100%",
28 | "padding-bottom": "100%",
29 | "background": "#303035",
30 | "position": "relative",
31 | "overflow": "hidden",
32 | })
33 | .appendTo(this.wrapper);
34 |
35 | // virtual size of the canvas (not actual pixel size)
36 | // this is relevant to draw commands inside ctx
37 | // the actual canvas just scales the drawing
38 | this.size = 500;
39 |
40 | // bounds of ROI in meters
41 | this.xmin = -10;
42 | this.xmax = 10;
43 | this.ymin = -10;
44 | this.ymax = 10;
45 |
46 | // canvas that shall be drawn upon
47 | this.canvas = $('')
48 | .css({
49 | "width": "100%",
50 | "height": "100%",
51 | "position": "absolute",
52 | "top": 0,
53 | "left": 0,
54 | "right": 0,
55 | "bottom": 0,
56 | })
57 | .appendTo(this.wrapper2);
58 |
59 | // context; draw commands are issued to the context
60 | this.ctx = this.canvas[0].getContext("2d");
61 |
62 | let that = this;
63 |
64 | this.canvas[0].addEventListener('pointermove', function(e) {
65 | let x = e.offsetX / that.canvas[0].clientWidth * (that.xmax - that.xmin) + that.xmin;
66 | let y = (1 - e.offsetY / that.canvas[0].clientHeight) * (that.ymax - that.ymin) + that.ymin;
67 | that.tip("(" + x.toFixed(3) + ", " + y.toFixed(3) + ")");
68 | });
69 |
70 | this.canvas[0].addEventListener('mousemove', function(e) {
71 | if(this.dragging) {
72 | let deltax = e.clientX - this.lastX;
73 | let deltay = e.clientY - this.lastY;
74 | that.pan(-deltax * (that.xmax - that.xmin) / that.size, deltay * (that.ymax - that.ymin) / that.size);
75 | this.lastX = e.clientX;
76 | this.lastY = e.clientY;
77 | }
78 | });
79 |
80 | this.canvas[0].addEventListener('click', function(e) {
81 | let x = e.offsetX / that.canvas[0].clientWidth * (that.xmax - that.xmin) + that.xmin;
82 | let y = (1 - e.offsetY / that.canvas[0].clientHeight) * (that.ymax - that.ymin) + that.ymin;
83 | that.onSpace2DClick({x: x, y: y});
84 | });
85 |
86 | this.canvas[0].addEventListener('mousedown', function(e) {
87 | if(e === null) e = window.event;
88 | if(!(e.buttons === 1)) return;
89 | if(e && e.preventDefault) e.preventDefault();
90 | this.dragging = true;
91 | this.lastX = e.clientX;
92 | this.lastY = e.clientY;
93 | });
94 |
95 | this.canvas[0].addEventListener('mouseup', function(e) {
96 | if(e === null) e = window.event;
97 | this.dragging = false;
98 | if(!(e.buttons === 1)) return;
99 | if(e && e.preventDefault) e.preventDefault();
100 | });
101 |
102 | this.canvas[0].addEventListener('mouseout', function(e) {
103 | if(e === null) e = window.event;
104 | this.dragging = false;
105 | if(!(e.buttons === 1)) return;
106 | if(e && e.preventDefault) e.preventDefault();
107 | });
108 |
109 | this.canvas[0].addEventListener('mouseleave', function(e) {
110 | if(e === null) e = window.event;
111 | this.dragging = false;
112 | if(!(e.buttons === 1)) return;
113 | if(e && e.preventDefault) e.preventDefault();
114 | });
115 |
116 | this.canvas[0].addEventListener('mousewheel', function(e) {
117 | if(e === null) e = window.event;
118 | if(e && e.preventDefault) e.preventDefault();
119 | else e.returnValue=false;
120 | let delta = 0;
121 | if(e.wheelDelta) { // IE/Opera
122 | delta = e.wheelDelta/120;
123 | } else if (e.detail) { // Mozilla/WebKit
124 | delta = -e.detail/3;
125 | }
126 | if(delta < 0) that.zoom(1.25);
127 | else if (delta > 0) that.zoom(0.8);
128 | });
129 |
130 | that.isScaling = false;
131 | that.scalingStartDist = 0;
132 | this.canvas[0].addEventListener('touchstart', function(e) {
133 | if(e.touches.length >= 2) {
134 | that.isScaling = true;
135 | that.scalingStartDist = Math.hypot(
136 | e.touches[0].pageX - e.touches[1].pageX,
137 | e.touches[0].pageY - e.touches[1].pageY,
138 | );
139 | that.panStartX = (e.touches[0].pageX + e.touches[1].pageX)/2;
140 | that.panStartY = (e.touches[0].pageY + e.touches[1].pageY)/2;
141 | } else {
142 | that.isScaling = false;
143 | }
144 | that.canvas.css({
145 | "transition": "transform 0.05s linear",
146 | "-webkit-transition": "-webkit-transform 0.05s linear",
147 | "-moz-transition": "-moz-transform 0.05s linear",
148 | "-ms-transition": "-ms-transform 0.05s linear",
149 | });
150 | });
151 |
152 | that.simZoomFactor = 1;
153 | this.canvas[0].addEventListener('touchmove', function(e) {
154 | if(!that.isScaling) return;
155 | let scalingDist = Math.hypot(
156 | e.touches[0].pageX - e.touches[1].pageX,
157 | e.touches[0].pageY - e.touches[1].pageY
158 | );
159 | that.panDistX = (e.touches[0].pageX + e.touches[1].pageX) / 2 - that.panStartX;
160 | that.panDistY = (e.touches[0].pageY + e.touches[1].pageY) / 2 - that.panStartY;
161 | that.simZoomFactor = that.scalingStartDist/scalingDist;
162 | e.target.style.webkitTransform = "scale(" + (1/that.simZoomFactor) + ") translateX(" + that.panDistX + "px) translateY(" + that.panDistY + "px)";
163 | e.target.style.mozTransform = "scale(" + (1/that.simZoomFactor) + ") translateX(" + that.panDistX + "px) translateY(" + that.panDistY + "px)";
164 | e.target.style.msTransform = "scale(" + (1/that.simZoomFactor) + ") translateX(" + that.panDistX + "px) translateY(" + that.panDistY + "px)";
165 | e.target.style.transform = "scale(" + (1/that.simZoomFactor) + ") translateX(" + that.panDistX + "px) translateY(" + that.panDistY + "px)";
166 | });
167 |
168 | this.canvas[0].addEventListener('touchend', function(e) {
169 | that.canvas.css({
170 | "transition": "",
171 | "-webkit-transition": "",
172 | "-moz-transition": "",
173 | "-ms-transition": "",
174 | });
175 | if(that.isScaling && e.touches.length < 2) {
176 | that.isScaling = false;
177 | that.pan(
178 | -that.panDistX * (that.xmax - that.xmin) / that.size / this.clientWidth * that.size,
179 | that.panDistY * (that.ymax - that.ymin) / that.size / this.clientHeight * that.size,
180 | );
181 | that.zoom(that.simZoomFactor);
182 | that.panDistX = 0;
183 | that.panDistY = 0;
184 | that.simZoomFactor = 0;
185 | e.target.style.transform = "";
186 | }
187 | });
188 | }
189 |
190 | onSpace2DClick({x, y}) {
191 |
192 | }
193 |
194 | pan(deltax, deltay) {
195 | this.xmin += deltax;
196 | this.xmax += deltax;
197 | this.ymin += deltay;
198 | this.ymax += deltay;
199 | this.draw(this.drawObjects);
200 | }
201 |
202 | zoom(factor) {
203 | if(((this.xmax - this.xmin) > 500 || (this.ymax - this.ymin) > 500) && factor > 1) return;
204 | if(((this.xmax - this.xmin) < 0.1 || (this.ymax - this.ymin) < 0.1) && factor < 1) return;
205 | let xcenter = (this.xmin + this.xmax) / 2;
206 | let ycenter = (this.ymin + this.ymax) / 2;
207 | let xspan = this.xmax - this.xmin;
208 | let yspan = this.ymax - this.ymin;
209 | this.xmin = xcenter - xspan/2 * factor;
210 | this.xmax = xcenter + xspan/2 * factor;
211 | this.ymin = ycenter - yspan/2 * factor;
212 | this.ymax = ycenter + yspan/2 * factor;
213 | this.draw(this.drawObjects);
214 | }
215 |
216 | setDefaultView({xcenter, ycenter, scale}) {
217 | this.defaultXCenter = xcenter;
218 | this.defaultYCenter = ycenter;
219 | this.defaultScale = scale;
220 |
221 | if(!this.alreadyInitializedDefaultView && this.defaultScale) {
222 | this.xmin = this.defaultXCenter - this.defaultScale / 2;
223 | this.xmax = this.defaultXCenter + this.defaultScale / 2;
224 | this.ymin = this.defaultYCenter - this.defaultScale / 2;
225 | this.ymax = this.defaultYCenter + this.defaultScale / 2;
226 | this.alreadyInitializedDefaultView = true;
227 | }
228 | }
229 |
230 | draw(drawObjects) {
231 | // converts x in meters to pixel-wise x based on current bounds
232 | let x2px = (x) => Math.floor(this.size * ((x - this.xmin) / (this.xmax - this.xmin)));
233 | // converts y in meters to pixel-wise y based on current bounds
234 | let y2py = (y) => Math.floor(this.size * (1 - (y - this.ymin) / (this.ymax - this.ymin)));
235 |
236 | // clear the drawing
237 | this.ctx.clearRect(0, 0, this.size, this.size);
238 | this.ctx.fillStyle = "#303035";
239 | this.ctx.fillRect(0, 0, this.size, this.size);
240 |
241 | // draw grid
242 | if(this.xmax - this.xmin < 50 ) {
243 | this.ctx.lineWidth = 1;
244 | this.ctx.strokeStyle = "#404040";
245 | this.ctx.beginPath();
246 |
247 | for(let x=Math.floor(this.xmin);x<=Math.ceil(this.xmax+0.001);x+=1) {
248 | this.ctx.moveTo(x2px(x),y2py(this.ymin));
249 | this.ctx.lineTo(x2px(x),y2py(this.ymax));
250 | }
251 |
252 | for(let y=Math.floor(this.ymin);y<=Math.ceil(this.ymax+0.001);y+=1) {
253 | this.ctx.moveTo(x2px(this.xmin),y2py(y));
254 | this.ctx.lineTo(x2px(this.xmax),y2py(y));
255 | }
256 |
257 | this.ctx.stroke();
258 | }
259 |
260 | this.ctx.lineWidth = 1;
261 | this.ctx.strokeStyle = "#505050";
262 | this.ctx.beginPath();
263 |
264 | for(let x=Math.floor(this.xmin/5)*5;x<=Math.ceil(this.xmax/5+0.001)*5;x+=5) {
265 | this.ctx.moveTo(x2px(x),y2py(this.ymin));
266 | this.ctx.lineTo(x2px(x),y2py(this.ymax));
267 | }
268 |
269 | for(let y=Math.floor(this.ymin/5)*5;y<=Math.ceil(this.ymax/5+0.001)*5;y+=5) {
270 | this.ctx.moveTo(x2px(this.xmin),y2py(y));
271 | this.ctx.lineTo(x2px(this.xmax),y2py(y));
272 | }
273 | this.ctx.stroke();
274 |
275 | // draw actual things specified by subclass
276 | // e.g. lines, points, whatever
277 |
278 | this.ctx.fillStyle = "#e0e0e0";
279 |
280 | for(let i in drawObjects) {
281 | let drawObject = drawObjects[i];
282 | if(drawObject.type === "path") {
283 | this.ctx.lineWidth = drawObject.lineWidth || 1;
284 | this.ctx.strokeStyle = drawObject.color || "#e0e0e0";
285 | this.ctx.beginPath();
286 | let px = x2px(drawObject.data[0]);
287 | let py = y2py(drawObject.data[1]);
288 | this.ctx.moveTo(px, py);
289 | for(let i=1;i this.size + 1) continue;
304 | if(py < -1) continue;
305 | if(py > this.size + 1) continue;
306 | this.ctx.fillRect(px, py, 3, 3);
307 | }
308 | } else if(drawObject.type === "text") {
309 | this.ctx.fillStyle = drawObject.color || "#e0e0e0";
310 | this.ctx.font = "12px Jetbrains Mono";
311 | this.ctx.fillText(drawObject.text, x2px(drawObject.x), y2py(drawObject.y));
312 | }
313 | }
314 | this.drawObjects = drawObjects;
315 | }
316 | }
317 |
318 | Space2DViewer.supportedTypes = [
319 | ];
320 |
321 | Space2DViewer.maxUpdateRate = 10.0;
322 |
323 | Viewer.registerViewer(Space2DViewer);
--------------------------------------------------------------------------------
/rosboard/html/css/index.css:
--------------------------------------------------------------------------------
1 | /* titillium-web-300 - latin */
2 | @font-face {
3 | font-family: 'Titillium Web';
4 | font-style: normal;
5 | font-weight: 300;
6 | src: url('../fonts/titillium-web-v10-latin-300.eot'); /* IE9 Compat Modes */
7 | src: local(''),
8 | url('../fonts/titillium-web-v10-latin-300.eot?#iefix') format('embedded-opentype'), /* IE6-IE8 */
9 | url('../fonts/titillium-web-v10-latin-300.woff2') format('woff2'), /* Super Modern Browsers */
10 | url('../fonts/titillium-web-v10-latin-300.woff') format('woff'), /* Modern Browsers */
11 | url('../fonts/titillium-web-v10-latin-300.ttf') format('truetype'), /* Safari, Android, iOS */
12 | url('../fonts/titillium-web-v10-latin-300.svg#TitilliumWeb') format('svg'); /* Legacy iOS */
13 | }
14 | /* titillium-web-700 - latin */
15 | @font-face {
16 | font-family: 'Titillium Web';
17 | font-style: normal;
18 | font-weight: 700;
19 | src: url('../fonts/titillium-web-v10-latin-700.eot'); /* IE9 Compat Modes */
20 | src: local(''),
21 | url('../fonts/titillium-web-v10-latin-700.eot?#iefix') format('embedded-opentype'), /* IE6-IE8 */
22 | url('../fonts/titillium-web-v10-latin-700.woff2') format('woff2'), /* Super Modern Browsers */
23 | url('../fonts/titillium-web-v10-latin-700.woff') format('woff'), /* Modern Browsers */
24 | url('../fonts/titillium-web-v10-latin-700.ttf') format('truetype'), /* Safari, Android, iOS */
25 | url('../fonts/titillium-web-v10-latin-700.svg#TitilliumWeb') format('svg'); /* Legacy iOS */
26 | }
27 |
28 | /* jetbrains-mono-300 - latin */
29 | @font-face {
30 | font-family: 'JetBrains Mono';
31 | font-style: normal;
32 | font-weight: 300;
33 | src: url('../fonts/jetbrains-mono-v6-latin-300.eot'); /* IE9 Compat Modes */
34 | src: local(''),
35 | url('../fonts/jetbrains-mono-v6-latin-300.eot?#iefix') format('embedded-opentype'), /* IE6-IE8 */
36 | url('../fonts/jetbrains-mono-v6-latin-300.woff2') format('woff2'), /* Super Modern Browsers */
37 | url('../fonts/jetbrains-mono-v6-latin-300.woff') format('woff'), /* Modern Browsers */
38 | url('../fonts/jetbrains-mono-v6-latin-300.ttf') format('truetype'), /* Safari, Android, iOS */
39 | url('../fonts/jetbrains-mono-v6-latin-300.svg#JetBrainsMono') format('svg'); /* Legacy iOS */
40 | }
41 | /* jetbrains-mono-700 - latin */
42 | @font-face {
43 | font-family: 'JetBrains Mono';
44 | font-style: normal;
45 | font-weight: 700;
46 | src: url('../fonts/jetbrains-mono-v6-latin-700.eot'); /* IE9 Compat Modes */
47 | src: local(''),
48 | url('../fonts/jetbrains-mono-v6-latin-700.eot?#iefix') format('embedded-opentype'), /* IE6-IE8 */
49 | url('../fonts/jetbrains-mono-v6-latin-700.woff2') format('woff2'), /* Super Modern Browsers */
50 | url('../fonts/jetbrains-mono-v6-latin-700.woff') format('woff'), /* Modern Browsers */
51 | url('../fonts/jetbrains-mono-v6-latin-700.ttf') format('truetype'), /* Safari, Android, iOS */
52 | url('../fonts/jetbrains-mono-v6-latin-700.svg#JetBrainsMono') format('svg'); /* Legacy iOS */
53 | }
54 |
55 | html {
56 | -webkit-text-size-adjust: none;
57 | touch-action: manipulation;
58 | margin:0; /* iOS prevent rubber banding */
59 | padding:0; /* iOS prevent rubber banding */
60 | overflow: hidden; /* iOS prevent rubber banding */
61 | }
62 |
63 | body {
64 | font-family: 'Titillium Web', sans-serif;
65 | background:#202020;
66 | color:#f0f0f0;
67 | touch-action: pan-x pan-y; /* prevent iOS late versions pinch zooming */
68 | overscroll-behavior-y: contain; /* ios/android prevent pull-to-refresh */
69 | position: absolute; /* iOS prevent rubber banding */
70 | width:100%; /* iOS prevent rubber banding */
71 | height:100%; /* iOS prevent rubber banding */
72 | overflow: auto; /* iOS prevent rubber banding */
73 | }
74 |
75 | div {touch-action: pan-x pan-y;} /* prevent iOS late versions pinch zooming */
76 |
77 | .mdl-layout-title {
78 | font-family: 'Titillium Web', sans-serif;
79 | }
80 |
81 | h1, h2, h3, h4, h5, h6, b, strong { font-weight:700; }
82 |
83 | pre, .monospace {
84 | font-family: 'JetBrains Mono', monospace;
85 | }
86 |
87 | .page-content {
88 | margin-bottom:20pt;
89 | min-height:calc(100vh - 110pt);
90 | }
91 |
92 | /* disable all text selection by default*/
93 | * {
94 | -webkit-user-select: none;
95 | -webkit-touch-callout: none;
96 | -moz-user-select: none;
97 | -ms-user-select: none;
98 | user-select: none;
99 | }
100 |
101 | /* enable text selection on input elements */
102 | input, textarea, *[contenteditable=true] {
103 | -webkit-touch-callout:default;
104 | -webkit-user-select:text;
105 | -moz-user-select:text;
106 | -ms-user-select:text;
107 | user-select:text;
108 | }
109 |
110 | .mdl-layout__content {
111 | background:#202020;
112 | }
113 |
114 | .card {
115 | border-radius:5pt;
116 | overflow:hidden;
117 | margin-left:20pt;
118 | margin-top:20pt;
119 | background:#303030;
120 | color:#c0c0c0;
121 | box-shadow:3pt 3pt 3pt rgba(0,0,0,0.2);
122 | width:calc(100% - 40pt);
123 | }
124 |
125 | .card-title {
126 | font-family:Titillium Web;
127 | font-size:12pt;
128 | color:#a0a0a0;
129 | padding-top:10pt;
130 | padding-left:15pt;
131 | padding-bottom:10pt;
132 | overflow:hidden;
133 | vertical-align:middle;
134 | line-height:15pt;
135 | overflow:hidden;
136 | text-overflow:ellipsis;
137 | width:calc( 100% - 45pt );
138 | }
139 |
140 | .card-title-tag {
141 | display:inline-block;
142 | color:#808080;
143 | font-size:9pt;
144 | padding-top:3pt;
145 | padding-bottom:3pt;
146 | padding-left:8pt;
147 | padding-right:8pt;
148 | margin-left:5pt;
149 | background:#f0f0f0;
150 | float:right;
151 | vertical-align:middle;
152 | }
153 |
154 | .card-buttons {
155 | position:absolute;
156 | display:flex;
157 | top:0;
158 | right:5pt;
159 | font-size:12pt;
160 | line-height:15pt;
161 | align-items:center;
162 | z-index:10;
163 | font-weight:700;
164 | height:35pt;
165 | }
166 |
167 | .card-button {
168 | width:16pt;
169 | height:16pt;
170 | background:#a05050;
171 | text-align:center;
172 | vertical-align:middle;
173 | font-size:9pt;
174 | line-height:16pt;
175 | border-radius:8pt;
176 | cursor:pointer;
177 | }
178 |
179 | .card-content {
180 | -webkit-transition: opacity 0.3s ease;
181 | -moz-transition: opacity 0.3s ease;
182 | -o-transition: opacity 0.3s ease;
183 | -ms-transition: opacity 0.3s ease;
184 | transition: opacity 0.3s ease;
185 | }
186 |
187 | @media screen and (min-width: 900px) {
188 | .card {
189 | display:inline-block;
190 | width:calc(50% - 40pt);
191 | }
192 | }
193 |
194 | @media screen and (min-width: 1200px) {
195 | .card {
196 | display:inline-block;
197 | width:calc(33% - 40pt);
198 | }
199 | }
200 |
201 | @media screen and (min-width: 1800px) {
202 | .card {
203 | display:inline-block;
204 | width:calc(25% - 40pt);
205 | }
206 | }
207 |
208 | .packery-drop-placeholder {
209 | outline: 3px dashed #444;
210 | outline-offset: -6px;
211 | /* transition position changing */
212 | -webkit-transition: -webkit-transform 0.2s;
213 | transition: transform 0.2s;
214 | }
215 |
216 | .mdl-layout__content {
217 | overflow-y: scroll; /* make scrollbar always visible to prevent "breathing" */
218 | }
219 |
220 | .mdl-data-table {
221 | color:#c0c0c0;
222 | background:#404040;
223 | }
224 |
225 | .mdl-navigation, .mdl-layout__drawer {
226 | background:#404040;
227 | color:#c0c0c0;
228 | }
229 |
230 | .mdl-data-table th {
231 | color:#e0e0e0;
232 | }
233 |
234 | .mdl-data-table-compact tr, .mdl-data-table-compact td {
235 | height: 24px !important;
236 | padding-top:3pt !important;
237 | padding-bottom:3pt !important;
238 | font-size:8pt;
239 | }
240 |
241 | .mdl-data-table-diagnostic {
242 | table-layout:fixed;
243 | width:100%;
244 | }
245 | .mdl-data-table-diagnostic tr, .mdl-data-table-diagnostic td {
246 | height: 24px !important;
247 | padding-top:3pt !important;
248 | padding-bottom:3pt !important;
249 | font-size:8pt;
250 | text-align:left;
251 | text-overflow:ellipsis;
252 | overflow:hidden;
253 | }
254 |
255 | .mdl-data-table-diagnostic thead tr {
256 | background:#404040;
257 | }
258 |
259 | .diagnostic-level-ok {
260 | color:#00AA00;
261 | }
262 |
263 | .diagnostic-level-warn {
264 | color:#c09000;
265 | }
266 |
267 | .diagnostic-level-error {
268 | color:#e05000;
269 | }
270 |
271 | .diagnostic-level-stale {
272 | color:#808080;
273 | }
274 |
275 | .mdl-data-table-diagnostic thead td:nth-child(1) i {
276 | padding-left:0pt;
277 | vertical-align: middle;
278 | }
279 |
280 | .mdl-data-table-diagnostic thead td:nth-child(2) {
281 | text-transform:uppercase;
282 | }
283 |
284 | .mdl-data-table-diagnostic td:nth-child(1) {
285 | width:5pt;
286 | padding-left:6pt;
287 | }
288 |
289 | .mdl-data-table-diagnostic td:nth-child(2) {
290 | width:40%;
291 | padding-left:2pt;
292 | }
293 |
294 | .mdl-data-table-diagnostic tbody tr {
295 | background:#303030;
296 | }
297 |
298 | .mdl-navigation__link {
299 | color:#c0c0c0 !important;
300 | text-overflow:ellipsis;
301 | overflow:hidden;
302 | /*direction: rtl;
303 | text-align: left;*/
304 | padding-top:5pt !important;
305 | padding-bottom:5pt !important;
306 | }
307 |
308 | .mdl-navigation__link:hover {
309 | color:#404040 !important;
310 | }
311 |
312 | .mdl-layout__drawer {
313 | width: 300px;
314 | left: -150px;
315 | }
316 |
317 | .mdl-layout__drawer.is-visible {
318 | left: 0;
319 | }
320 |
321 | .topics-nav-title {
322 | text-transform:uppercase;
323 | color:#808080;
324 | font-size:10pt;
325 | font-weight:700;
326 | padding-left:10pt;
327 | border-bottom:1px dotted #505050;
328 | padding-top:10pt;
329 | padding-bottom:10pt;
330 | }
331 |
332 | /* width */
333 | ::-webkit-scrollbar {
334 | width: 10px;
335 | }
336 |
337 | /* Track */
338 | ::-webkit-scrollbar-track {
339 | background: #202020;
340 | }
341 |
342 | /* Handle */
343 | ::-webkit-scrollbar-thumb {
344 | background: #c0c0c0;
345 | }
346 |
347 | /* Handle on hover */
348 | ::-webkit-scrollbar-thumb:hover {
349 | background: #44b0e0;
350 | }
351 |
352 | .loader-container {
353 | position:absolute;
354 | display: flex;
355 | top: 0;
356 | left: 0;
357 | width: 100%;
358 | align-items: center;
359 | height: 100%;
360 | }
361 |
362 | .loader {
363 | color: #ffffff;
364 | font-size: 30px;
365 | text-indent: -9999em;
366 | overflow: hidden;
367 | width: 1em;
368 | height: 1em;
369 | border-radius: 50%;
370 | margin: 72px auto;
371 | position: relative;
372 | -webkit-transform: translateZ(0);
373 | -ms-transform: translateZ(0);
374 | transform: translateZ(0);
375 | -webkit-animation: load6 1.7s infinite ease, round 1.7s infinite ease;
376 | animation: load6 1.7s infinite ease, round 1.7s infinite ease;
377 | }
378 | @-webkit-keyframes load6 {
379 | 0% {
380 | box-shadow: 0 -0.83em 0 -0.4em, 0 -0.83em 0 -0.42em, 0 -0.83em 0 -0.44em, 0 -0.83em 0 -0.46em, 0 -0.83em 0 -0.477em;
381 | }
382 | 5%,
383 | 95% {
384 | box-shadow: 0 -0.83em 0 -0.4em, 0 -0.83em 0 -0.42em, 0 -0.83em 0 -0.44em, 0 -0.83em 0 -0.46em, 0 -0.83em 0 -0.477em;
385 | }
386 | 10%,
387 | 59% {
388 | box-shadow: 0 -0.83em 0 -0.4em, -0.087em -0.825em 0 -0.42em, -0.173em -0.812em 0 -0.44em, -0.256em -0.789em 0 -0.46em, -0.297em -0.775em 0 -0.477em;
389 | }
390 | 20% {
391 | box-shadow: 0 -0.83em 0 -0.4em, -0.338em -0.758em 0 -0.42em, -0.555em -0.617em 0 -0.44em, -0.671em -0.488em 0 -0.46em, -0.749em -0.34em 0 -0.477em;
392 | }
393 | 38% {
394 | box-shadow: 0 -0.83em 0 -0.4em, -0.377em -0.74em 0 -0.42em, -0.645em -0.522em 0 -0.44em, -0.775em -0.297em 0 -0.46em, -0.82em -0.09em 0 -0.477em;
395 | }
396 | 100% {
397 | box-shadow: 0 -0.83em 0 -0.4em, 0 -0.83em 0 -0.42em, 0 -0.83em 0 -0.44em, 0 -0.83em 0 -0.46em, 0 -0.83em 0 -0.477em;
398 | }
399 | }
400 | @keyframes load6 {
401 | 0% {
402 | box-shadow: 0 -0.83em 0 -0.4em, 0 -0.83em 0 -0.42em, 0 -0.83em 0 -0.44em, 0 -0.83em 0 -0.46em, 0 -0.83em 0 -0.477em;
403 | }
404 | 5%,
405 | 95% {
406 | box-shadow: 0 -0.83em 0 -0.4em, 0 -0.83em 0 -0.42em, 0 -0.83em 0 -0.44em, 0 -0.83em 0 -0.46em, 0 -0.83em 0 -0.477em;
407 | }
408 | 10%,
409 | 59% {
410 | box-shadow: 0 -0.83em 0 -0.4em, -0.087em -0.825em 0 -0.42em, -0.173em -0.812em 0 -0.44em, -0.256em -0.789em 0 -0.46em, -0.297em -0.775em 0 -0.477em;
411 | }
412 | 20% {
413 | box-shadow: 0 -0.83em 0 -0.4em, -0.338em -0.758em 0 -0.42em, -0.555em -0.617em 0 -0.44em, -0.671em -0.488em 0 -0.46em, -0.749em -0.34em 0 -0.477em;
414 | }
415 | 38% {
416 | box-shadow: 0 -0.83em 0 -0.4em, -0.377em -0.74em 0 -0.42em, -0.645em -0.522em 0 -0.44em, -0.775em -0.297em 0 -0.46em, -0.82em -0.09em 0 -0.477em;
417 | }
418 | 100% {
419 | box-shadow: 0 -0.83em 0 -0.4em, 0 -0.83em 0 -0.42em, 0 -0.83em 0 -0.44em, 0 -0.83em 0 -0.46em, 0 -0.83em 0 -0.477em;
420 | }
421 | }
422 | @-webkit-keyframes round {
423 | 0% {
424 | -webkit-transform: rotate(0deg);
425 | transform: rotate(0deg);
426 | }
427 | 100% {
428 | -webkit-transform: rotate(360deg);
429 | transform: rotate(360deg);
430 | }
431 | }
432 | @keyframes round {
433 | 0% {
434 | -webkit-transform: rotate(0deg);
435 | transform: rotate(0deg);
436 | }
437 | 100% {
438 | -webkit-transform: rotate(360deg);
439 | transform: rotate(360deg);
440 | }
441 | }
442 |
--------------------------------------------------------------------------------
/rosboard/html/js/draggabilly.pkgd.min.js:
--------------------------------------------------------------------------------
1 | /*!
2 | * Draggabilly PACKAGED v2.1.1
3 | * Make that shiz draggable
4 | * http://draggabilly.desandro.com
5 | * MIT license
6 | */
7 |
8 | !function(t,i){"function"==typeof define&&define.amd?define("jquery-bridget/jquery-bridget",["jquery"],function(e){i(t,e)}):"object"==typeof module&&module.exports?module.exports=i(t,require("jquery")):t.jQueryBridget=i(t,t.jQuery)}(window,function(t,i){function e(e,r,a){function d(t,i,n){var o,r="$()."+e+'("'+i+'")';return t.each(function(t,d){var h=a.data(d,e);if(!h)return void s(e+" not initialized. Cannot call methods, i.e. "+r);var u=h[i];if(!u||"_"==i.charAt(0))return void s(r+" is not a valid method");var c=u.apply(h,n);o=void 0===o?c:o}),void 0!==o?o:t}function h(t,i){t.each(function(t,n){var o=a.data(n,e);o?(o.option(i),o._init()):(o=new r(n,i),a.data(n,e,o))})}a=a||i||t.jQuery,a&&(r.prototype.option||(r.prototype.option=function(t){a.isPlainObject(t)&&(this.options=a.extend(!0,this.options,t))}),a.fn[e]=function(t){if("string"==typeof t){var i=o.call(arguments,1);return d(this,t,i)}return h(this,t),this},n(a))}function n(t){!t||t&&t.bridget||(t.bridget=e)}var o=Array.prototype.slice,r=t.console,s="undefined"==typeof r?function(){}:function(t){r.error(t)};return n(i||t.jQuery),e}),function(t,i){"function"==typeof define&&define.amd?define("get-size/get-size",[],function(){return i()}):"object"==typeof module&&module.exports?module.exports=i():t.getSize=i()}(window,function(){function t(t){var i=parseFloat(t),e=-1==t.indexOf("%")&&!isNaN(i);return e&&i}function i(){}function e(){for(var t={width:0,height:0,innerWidth:0,innerHeight:0,outerWidth:0,outerHeight:0},i=0;h>i;i++){var e=d[i];t[e]=0}return t}function n(t){var i=getComputedStyle(t);return i||a("Style returned "+i+". Are you running this code in a hidden iframe on Firefox? See http://bit.ly/getsizebug1"),i}function o(){if(!u){u=!0;var i=document.createElement("div");i.style.width="200px",i.style.padding="1px 2px 3px 4px",i.style.borderStyle="solid",i.style.borderWidth="1px 2px 3px 4px",i.style.boxSizing="border-box";var e=document.body||document.documentElement;e.appendChild(i);var o=n(i);r.isBoxSizeOuter=s=200==t(o.width),e.removeChild(i)}}function r(i){if(o(),"string"==typeof i&&(i=document.querySelector(i)),i&&"object"==typeof i&&i.nodeType){var r=n(i);if("none"==r.display)return e();var a={};a.width=i.offsetWidth,a.height=i.offsetHeight;for(var u=a.isBorderBox="border-box"==r.boxSizing,c=0;h>c;c++){var p=d[c],f=r[p],g=parseFloat(f);a[p]=isNaN(g)?0:g}var l=a.paddingLeft+a.paddingRight,v=a.paddingTop+a.paddingBottom,m=a.marginLeft+a.marginRight,y=a.marginTop+a.marginBottom,b=a.borderLeftWidth+a.borderRightWidth,P=a.borderTopWidth+a.borderBottomWidth,E=u&&s,_=t(r.width);_!==!1&&(a.width=_+(E?0:l+b));var x=t(r.height);return x!==!1&&(a.height=x+(E?0:v+P)),a.innerWidth=a.width-(l+b),a.innerHeight=a.height-(v+P),a.outerWidth=a.width+m,a.outerHeight=a.height+y,a}}var s,a="undefined"==typeof console?i:function(t){console.error(t)},d=["paddingLeft","paddingRight","paddingTop","paddingBottom","marginLeft","marginRight","marginTop","marginBottom","borderLeftWidth","borderRightWidth","borderTopWidth","borderBottomWidth"],h=d.length,u=!1;return r}),function(t,i){"function"==typeof define&&define.amd?define("ev-emitter/ev-emitter",i):"object"==typeof module&&module.exports?module.exports=i():t.EvEmitter=i()}("undefined"!=typeof window?window:this,function(){function t(){}var i=t.prototype;return i.on=function(t,i){if(t&&i){var e=this._events=this._events||{},n=e[t]=e[t]||[];return-1==n.indexOf(i)&&n.push(i),this}},i.once=function(t,i){if(t&&i){this.on(t,i);var e=this._onceEvents=this._onceEvents||{},n=e[t]=e[t]||{};return n[i]=!0,this}},i.off=function(t,i){var e=this._events&&this._events[t];if(e&&e.length){var n=e.indexOf(i);return-1!=n&&e.splice(n,1),this}},i.emitEvent=function(t,i){var e=this._events&&this._events[t];if(e&&e.length){var n=0,o=e[n];i=i||[];for(var r=this._onceEvents&&this._onceEvents[t];o;){var s=r&&r[o];s&&(this.off(t,o),delete r[o]),o.apply(this,i),n+=s?0:1,o=e[n]}return this}},t}),function(t,i){"function"==typeof define&&define.amd?define("unipointer/unipointer",["ev-emitter/ev-emitter"],function(e){return i(t,e)}):"object"==typeof module&&module.exports?module.exports=i(t,require("ev-emitter")):t.Unipointer=i(t,t.EvEmitter)}(window,function(t,i){function e(){}function n(){}var o=n.prototype=Object.create(i.prototype);o.bindStartEvent=function(t){this._bindStartEvent(t,!0)},o.unbindStartEvent=function(t){this._bindStartEvent(t,!1)},o._bindStartEvent=function(i,e){e=void 0===e?!0:!!e;var n=e?"addEventListener":"removeEventListener";t.navigator.pointerEnabled?i[n]("pointerdown",this):t.navigator.msPointerEnabled?i[n]("MSPointerDown",this):(i[n]("mousedown",this),i[n]("touchstart",this))},o.handleEvent=function(t){var i="on"+t.type;this[i]&&this[i](t)},o.getTouch=function(t){for(var i=0;i3||Math.abs(t.y)>3},o.pointerUp=function(t,i){this.emitEvent("pointerUp",[t,i]),this._dragPointerUp(t,i)},o._dragPointerUp=function(t,i){this.isDragging?this._dragEnd(t,i):this._staticClick(t,i)},o._dragStart=function(t,e){this.isDragging=!0,this.dragStartPoint=i.getPointerPoint(e),this.isPreventingClicks=!0,this.dragStart(t,e)},o.dragStart=function(t,i){this.emitEvent("dragStart",[t,i])},o._dragMove=function(t,i,e){this.isDragging&&this.dragMove(t,i,e)},o.dragMove=function(t,i,e){t.preventDefault(),this.emitEvent("dragMove",[t,i,e])},o._dragEnd=function(t,i){this.isDragging=!1,setTimeout(function(){delete this.isPreventingClicks}.bind(this)),this.dragEnd(t,i)},o.dragEnd=function(t,i){this.emitEvent("dragEnd",[t,i])},o.onclick=function(t){this.isPreventingClicks&&t.preventDefault()},o._staticClick=function(t,i){if(!this.isIgnoringMouseUp||"mouseup"!=t.type){var e=t.target.nodeName;("INPUT"==e||"TEXTAREA"==e)&&t.target.focus(),this.staticClick(t,i),"mouseup"!=t.type&&(this.isIgnoringMouseUp=!0,setTimeout(function(){delete this.isIgnoringMouseUp}.bind(this),400))}},o.staticClick=function(t,i){this.emitEvent("staticClick",[t,i])},n.getPointerPoint=i.getPointerPoint,n}),function(t,i){"function"==typeof define&&define.amd?define(["get-size/get-size","unidragger/unidragger"],function(e,n){return i(t,e,n)}):"object"==typeof module&&module.exports?module.exports=i(t,require("get-size"),require("unidragger")):t.Draggabilly=i(t,t.getSize,t.Unidragger)}(window,function(t,i,e){function n(){}function o(t,i){for(var e in i)t[e]=i[e];return t}function r(t){return t instanceof HTMLElement}function s(t,i){this.element="string"==typeof t?d.querySelector(t):t,f&&(this.$element=f(this.element)),this.options=o({},this.constructor.defaults),this.option(i),this._create()}function a(t,i,e){return e=e||"round",i?Math[e](t/i)*i:t}var d=t.document,h=t.requestAnimationFrame||t.webkitRequestAnimationFrame||t.mozRequestAnimationFrame,u=0;h||(h=function(t){var i=(new Date).getTime(),e=Math.max(0,16-(i-u)),n=setTimeout(t,e);return u=i+e,n});var c=d.documentElement,p="string"==typeof c.style.transform?"transform":"WebkitTransform",f=t.jQuery,g=s.prototype=Object.create(e.prototype);s.defaults={},g.option=function(t){o(this.options,t)};var l={relative:!0,absolute:!0,fixed:!0};return g._create=function(){this.position={},this._getPosition(),this.startPoint={x:0,y:0},this.dragPoint={x:0,y:0},this.startPosition=o({},this.position);var t=getComputedStyle(this.element);l[t.position]||(this.element.style.position="relative"),this.enable(),this.setHandles()},g.setHandles=function(){this.handles=this.options.handle?this.element.querySelectorAll(this.options.handle):[this.element],this.bindHandles()},g.dispatchEvent=function(i,e,n){var o=[e].concat(n);this.emitEvent(i,o);var r=t.jQuery;if(r&&this.$element)if(e){var s=r.Event(e);s.type=i,this.$element.trigger(s,n)}else this.$element.trigger(i,n)},g._getPosition=function(){var t=getComputedStyle(this.element),i=this._getPositionCoord(t.left,"width"),e=this._getPositionCoord(t.top,"height");this.position.x=isNaN(i)?0:i,this.position.y=isNaN(e)?0:e,this._addTransformPosition(t)},g._getPositionCoord=function(t,e){if(-1!=t.indexOf("%")){var n=i(this.element.parentNode);return n?parseFloat(t)/100*n[e]:0}return parseInt(t,10)},g._addTransformPosition=function(t){var i=t[p];if(0===i.indexOf("matrix")){var e=i.split(","),n=0===i.indexOf("matrix3d")?12:4,o=parseInt(e[n],10),r=parseInt(e[n+1],10);this.position.x+=o,this.position.y+=r}},g.pointerDown=function(t,i){this._dragPointerDown(t,i);var e=d.activeElement;e&&e.blur&&e!=d.body&&e.blur(),this._bindPostStartEvents(t),this.element.classList.add("is-pointer-down"),this.dispatchEvent("pointerDown",t,[i])},g.pointerMove=function(t,i){var e=this._dragPointerMove(t,i);this.dispatchEvent("pointerMove",t,[i,e]),this._dragMove(t,i,e)},g.dragStart=function(t,i){this.isEnabled&&(this._getPosition(),this.measureContainment(),this.startPosition.x=this.position.x,this.startPosition.y=this.position.y,this.setLeftTop(),this.dragPoint.x=0,this.dragPoint.y=0,this.element.classList.add("is-dragging"),this.dispatchEvent("dragStart",t,[i]),this.animate())},g.measureContainment=function(){var t=this.options.containment;if(t){var e=r(t)?t:"string"==typeof t?d.querySelector(t):this.element.parentNode,n=i(this.element),o=i(e),s=this.element.getBoundingClientRect(),a=e.getBoundingClientRect(),h=o.borderLeftWidth+o.borderRightWidth,u=o.borderTopWidth+o.borderBottomWidth,c=this.relativeStartPosition={x:s.left-(a.left+o.borderLeftWidth),y:s.top-(a.top+o.borderTopWidth)};this.containSize={width:o.width-h-c.x-n.width,height:o.height-u-c.y-n.height}}},g.dragMove=function(t,i,e){if(this.isEnabled){var n=e.x,o=e.y,r=this.options.grid,s=r&&r[0],d=r&&r[1];n=a(n,s),o=a(o,d),n=this.containDrag("x",n,s),o=this.containDrag("y",o,d),n="y"==this.options.axis?0:n,o="x"==this.options.axis?0:o,this.position.x=this.startPosition.x+n,this.position.y=this.startPosition.y+o,this.dragPoint.x=n,this.dragPoint.y=o,this.dispatchEvent("dragMove",t,[i,e])}},g.containDrag=function(t,i,e){if(!this.options.containment)return i;var n="x"==t?"width":"height",o=this.relativeStartPosition[t],r=a(-o,e,"ceil"),s=this.containSize[n];return s=a(s,e,"floor"),Math.min(s,Math.max(r,i))},g.pointerUp=function(t,i){this.element.classList.remove("is-pointer-down"),this.dispatchEvent("pointerUp",t,[i]),this._dragPointerUp(t,i)},g.dragEnd=function(t,i){this.isEnabled&&(p&&(this.element.style[p]="",this.setLeftTop()),this.element.classList.remove("is-dragging"),this.dispatchEvent("dragEnd",t,[i]))},g.animate=function(){if(this.isDragging){this.positionDrag();var t=this;h(function(){t.animate()})}},g.setLeftTop=function(){this.element.style.left=this.position.x+"px",this.element.style.top=this.position.y+"px"},g.positionDrag=function(){this.element.style[p]="translate3d( "+this.dragPoint.x+"px, "+this.dragPoint.y+"px, 0)"},g.staticClick=function(t,i){this.dispatchEvent("staticClick",t,[i])},g.enable=function(){this.isEnabled=!0},g.disable=function(){this.isEnabled=!1,this.isDragging&&this.dragEnd()},g.destroy=function(){this.disable(),this.element.style[p]="",this.element.style.left="",this.element.style.top="",this.element.style.position="",this.unbindHandles(),this.$element&&this.$element.removeData("draggabilly")},g._init=n,f&&f.bridget&&f.bridget("draggabilly",s),s});
--------------------------------------------------------------------------------
/rosboard/compression.py:
--------------------------------------------------------------------------------
1 | import base64
2 | import io
3 | import numpy as np
4 | from rosboard.cv_bridge import imgmsg_to_cv2
5 |
6 | try:
7 | import simplejpeg
8 | except ImportError:
9 | simplejpeg = None
10 | try:
11 | import cv2
12 | print("simplejpeg not found. Falling back to cv2 for JPEG encoding.")
13 | except ImportError:
14 | cv2 = None
15 | try:
16 | import PIL
17 | from PIL import Image
18 | print("simplejpeg not found. Falling back to PIL for JPEG encoding.")
19 | except ImportError:
20 | PIL = None
21 |
22 | def decode_jpeg(input_bytes):
23 | if simplejpeg:
24 | return simplejpeg.decode_jpeg(input_bytes)
25 | elif cv2:
26 | return cv2.imdecode(np.frombuffer(input_bytes, dtype=np.uint8), cv2.IMREAD_COLOR)[:,:,::-1]
27 | elif PIL:
28 | return np.asarray(Image.open(io.BytesIO(input_bytes)))
29 |
30 | def encode_jpeg(img):
31 | if simplejpeg:
32 | if len(img.shape) == 2:
33 | img = np.expand_dims(img, axis=2)
34 | if not img.flags['C_CONTIGUOUS']:
35 | img = img.copy(order='C')
36 | return simplejpeg.encode_jpeg(img, colorspace = "GRAY", quality = 50)
37 | elif len(img.shape) == 3:
38 | if not img.flags['C_CONTIGUOUS']:
39 | img = img.copy(order='C')
40 | if img.shape[2] == 1:
41 | return simplejpeg.encode_jpeg(img, colorspace = "GRAY", quality = 50)
42 | elif img.shape[2] == 4:
43 | return simplejpeg.encode_jpeg(img, colorspace = "RGBA", quality = 50)
44 | elif img.shape[2] == 3:
45 | return simplejpeg.encode_jpeg(img, colorspace = "RGB", quality = 50)
46 | else:
47 | return b''
48 | elif cv2:
49 | if len(img.shape) == 3 and img.shape[2] == 3:
50 | img = img[:,:,::-1]
51 | return cv2.imencode('.jpg', img, [cv2.IMWRITE_JPEG_QUALITY, 50])[1].tobytes()
52 | elif PIL:
53 | pil_img = Image.fromarray(img)
54 | buffered = io.BytesIO()
55 | pil_img.save(buffered, format="JPEG", quality = 50)
56 | return buffered.getvalue()
57 |
58 | _PCL2_DATATYPES_NUMPY_MAP = {
59 | 1: np.int8,
60 | 2: np.uint8,
61 | 3: np.int16,
62 | 4: np.uint16,
63 | 5: np.int32,
64 | 6: np.uint32,
65 | 7: np.float32,
66 | 8: np.float64,
67 | }
68 |
69 | def decode_pcl2(cloud, field_names=None, skip_nans=False, uvs=[]):
70 | """
71 | Read points from a sensor_msgs.PointCloud2 message.
72 |
73 | :param cloud: The point cloud to read from sensor_msgs.PointCloud2.
74 | :param field_names: The names of fields to read. If None, read all fields.
75 | (Type: Iterable, Default: None)
76 | :param skip_nans: If True, then don't return any point with a NaN value.
77 | (Type: Bool, Default: False)
78 | :param uvs: If specified, then only return the points at the given
79 | coordinates. (Type: Iterable, Default: empty list)
80 | :return: numpy.recarray with values for each point.
81 | """
82 |
83 | assert cloud.point_step * cloud.width * cloud.height == len(cloud.data), \
84 | 'length of data does not match point_step * width * height'
85 |
86 | all_field_names = []
87 | np_struct = []
88 | total_used_bytes = 0
89 | for field in cloud.fields:
90 | all_field_names.append(field.name)
91 | assert field.datatype in _PCL2_DATATYPES_NUMPY_MAP, \
92 | 'invalid datatype %d specified for field %s' % (field.datatype, field.name)
93 | field_np_datatype = _PCL2_DATATYPES_NUMPY_MAP[field.datatype]
94 | np_struct.append((field.name, field_np_datatype))
95 | total_used_bytes += np.nbytes[field_np_datatype]
96 |
97 | assert cloud.point_step >= total_used_bytes, \
98 | 'error: total byte sizes of fields exceeds point_step'
99 |
100 | if cloud.point_step > total_used_bytes:
101 | np_struct.append(('unused_bytes', np.uint8, cloud.point_step - total_used_bytes))
102 |
103 | points = np.frombuffer(cloud.data, dtype=np_struct).view(dtype=np.recarray)
104 |
105 | if skip_nans:
106 | nan_indexes = None
107 | for field_name in all_field_names:
108 | if nan_indexes is None:
109 | nan_indexes = np.isnan(points[field_name])
110 | else:
111 | nan_indexes = nan_indexes | np.isnan(points[field_name])
112 |
113 | points = points[~nan_indexes]
114 |
115 | if uvs:
116 | fetch_indexes = [(v * cloud.width + u) for u, v in uvs]
117 | points = points[fetch_indexes]
118 |
119 | # if endianness between cloud and system doesn't match then byteswap everything
120 | if cloud.is_bigendian == np.little_endian:
121 | points = points.byteswap()
122 |
123 | if field_names is None:
124 | return points
125 | else:
126 | return points[list(field_names)]
127 |
128 | def compress_compressed_image(msg, output):
129 | output["data"] = []
130 | output["__comp"] = ["data"]
131 |
132 | if simplejpeg is None and cv2 is None and PIL is None:
133 | output["_error"] = "Please install simplejpeg, cv2 (OpenCV), or PIL (pillow) for image support."
134 | return
135 |
136 | # if message is already in jpeg format and small enough just pass it through
137 | if len(msg.data) < 250000 and "jpeg" in msg.format:
138 | output["_data_jpeg"] = base64.b64encode(bytearray(msg.data)).decode()
139 | return
140 |
141 | # else recompress it
142 | try:
143 | img = decode_jpeg(bytearray(msg.data))
144 | original_shape = img.shape
145 | if img.shape[0] > 800 or img.shape[1] > 800:
146 | stride = int(np.ceil(max(img.shape[0] / 800.0, img.shape[1] / 800.0)))
147 | img = img[::stride,::stride]
148 | img_jpeg = encode_jpeg(img)
149 | except Exception as e:
150 | output["_error"] = "Error: %s" % str(e)
151 | return
152 | output["_data_jpeg"] = base64.b64encode(img_jpeg).decode()
153 | output["_data_shape"] = list(original_shape)
154 |
155 |
156 | def compress_image(msg, output):
157 | output["data"] = []
158 | output["__comp"] = ["data"]
159 |
160 | if simplejpeg is None and cv2 is None and PIL is None:
161 | output["_error"] = "Please install simplejpeg, cv2 (OpenCV), or PIL (pillow) for image support."
162 | return
163 |
164 | cv2_img = imgmsg_to_cv2(msg, flip_channels = True)
165 | original_shape = cv2_img.shape
166 |
167 | # if image has alpha channel, cut it out since we will ultimately compress as jpeg
168 | if len(cv2_img.shape) == 3 and cv2_img.shape[2] == 4:
169 | cv2_img = cv2_img[:,:,0:3]
170 |
171 | # if image has only 2 channels, expand it to 3 channels for visualization
172 | # channel 0 -> R, channel 1 -> G, zeros -> B
173 | if len(cv2_img.shape) == 3 and cv2_img.shape[2] == 2:
174 | cv2_img = np.stack((cv2_img[:,:,0], cv2_img[:,:,1], np.zeros(cv2_img[:,:,0].shape)), axis = -1)
175 |
176 | # enforce <800px max dimension, and do a stride-based resize
177 | if cv2_img.shape[0] > 800 or cv2_img.shape[1] > 800:
178 | stride = int(np.ceil(max(cv2_img.shape[0] / 800.0, cv2_img.shape[1] / 800.0)))
179 | cv2_img = cv2_img[::stride,::stride]
180 |
181 | # if image format isn't already uint8, make it uint8 for visualization purposes
182 | if cv2_img.dtype != np.uint8:
183 | if cv2_img.dtype == np.uint64:
184 | # keep only the most significant 8 bits (0 to 255)
185 | cv2_img = (cv2_img >> 56).astype(np.uint8)
186 | elif cv2_img.dtype == np.uint32:
187 | # keep only the most significant 8 bits (0 to 255)
188 | cv2_img = (cv2_img >> 24).astype(np.uint8)
189 | elif cv2_img.dtype == np.uint16:
190 | # keep only the most significant 8 bits (0 to 255)
191 | cv2_img = (cv2_img >> 8).astype(np.uint8)
192 | elif cv2_img.dtype == np.float16 or cv2_img.dtype == np.float32 or cv2_img.dtype == np.float64:
193 | # map the float range (0 to 1) to uint8 range (0 to 255)
194 | cv2_img = np.clip(cv2_img * 255, 0, 255).astype(np.uint8)
195 |
196 | try:
197 | img_jpeg = encode_jpeg(cv2_img)
198 | output["_data_jpeg"] = base64.b64encode(img_jpeg).decode()
199 | output["_data_shape"] = original_shape
200 | except OSError as e:
201 | output["_error"] = str(e)
202 |
203 | def compress_occupancy_grid(msg, output):
204 | output["_data"] = []
205 | output["__comp"] = ["data"]
206 |
207 | if simplejpeg is None and cv2 is None and PIL is None:
208 | output["_error"] = "Please install simplejpeg, cv2 (OpenCV), or PIL (pillow) for image support."
209 | return
210 |
211 | try:
212 | occupancy_map = np.array(msg.data, dtype=np.uint16).reshape(msg.info.height, msg.info.width)[::-1,:]
213 |
214 | while occupancy_map.shape[0] > 800 or occupancy_map.shape[1] > 800:
215 | occupancy_map = occupancy_map[::2,::2]
216 |
217 | cv2_img = ((100 - occupancy_map) * 10 // 4).astype(np.uint8) # *10//4 is int approx to *255.0/100.0
218 | cv2_img = np.stack((cv2_img,)*3, axis = -1) # greyscale to rgb
219 | cv2_img[occupancy_map < 0] = [255, 127, 0]
220 | cv2_img[occupancy_map > 100] = [255, 0, 0]
221 |
222 | except Exception as e:
223 | output["_error"] = str(e)
224 | try:
225 | img_jpeg = encode_jpeg(cv2_img)
226 | output["_data_jpeg"] = base64.b64encode(img_jpeg).decode()
227 | except OSError as e:
228 | output["_error"] = str(e)
229 |
230 | DATATYPE_MAPPING_PCL2_NUMPY = {
231 | 1: np.int8,
232 | 2: np.uint8,
233 | 3: np.int16,
234 | 4: np.uint16,
235 | 5: np.int32,
236 | 6: np.uint32,
237 | 7: np.float32,
238 | 8: np.float64,
239 | }
240 |
241 | def compress_point_cloud2(msg, output):
242 | # assuming fields are ('x', 'y', 'z', ...),
243 | # compression scheme is:
244 | # msg['_data_uint16'] = {
245 | # bounds: [ xmin, xmax, ymin, ymax, zmin, zmax, ... ]
246 | # points: string: base64 encoded bytearray of struct { uint16 x_frac; uint16 y_frac; uint16 z_frac;}
247 | # }
248 | # where x_frac = 0 maps to xmin and x_frac = 65535 maps to xmax
249 | # i.e. we are encoding all the floats as uint16 values where 0 represents the min value in the entire dataset and
250 | # 65535 represents the max value in the dataset, and bounds: [...] holds information on those bounds so the
251 | # client can decode back to a float
252 |
253 | output["data"] = []
254 | output["__comp"] = ["data"]
255 |
256 | field_names = [field.name for field in msg.fields]
257 |
258 | if "x" not in field_names or "y" not in field_names:
259 | output["_error"] = "PointCloud2 error: must contain at least 'x' and 'y' fields for visualization"
260 | return
261 |
262 | if "z" in field_names:
263 | decode_fields = ("x", "y", "z")
264 | else:
265 | decode_fields = ("x", "y")
266 |
267 | try:
268 | points = decode_pcl2(msg, field_names = decode_fields, skip_nans = True)
269 | except AssertionError as e:
270 | output["_error"] = "PointCloud2 error: %s" % str(e)
271 |
272 | if points.size > 65536:
273 | output["_warn"] = "Point cloud too large, randomly subsampling to 65536 points."
274 | idx = np.random.randint(points.size, size=65536)
275 | points = points[idx]
276 |
277 | xpoints = points['x'].astype(np.float32)
278 | xmax = np.max(xpoints)
279 | xmin = np.min(xpoints)
280 | if xmax - xmin < 1.0:
281 | xmax = xmin + 1.0
282 | xpoints_uint16 = (65535 * (xpoints - xmin) / (xmax - xmin)).astype(np.uint16)
283 |
284 | ypoints = points['y'].astype(np.float32)
285 | ymax = np.max(ypoints)
286 | ymin = np.min(ypoints)
287 | if ymax - ymin < 1.0:
288 | ymax = ymin + 1.0
289 | ypoints_uint16 = (65535 * (ypoints - ymin) / (ymax - ymin)).astype(np.uint16)
290 |
291 | if "z" in field_names:
292 | zpoints = points['z'].astype(np.float32)
293 | zmax = np.max(zpoints)
294 | zmin = np.min(zpoints)
295 | if zmax - zmin < 1.0:
296 | zmax = zmin + 1.0
297 | zpoints_uint16 = (65535 * (zpoints - zmin) / (zmax - zmin)).astype(np.uint16)
298 | else:
299 | zmax = 1.0
300 | zmin = 0.0
301 | zpoints_uint16 = ypoints_uint16 * 0
302 |
303 | bounds_uint16 = [xmin, xmax, ymin, ymax, zmin, zmax]
304 | if np.little_endian:
305 | points_uint16 = np.stack((xpoints_uint16, ypoints_uint16, zpoints_uint16),1).ravel().view(dtype=np.uint8)
306 | else:
307 | points_uint16 = np.stack((xpoints_uint16, ypoints_uint16, zpoints_uint16),1).ravel().byteswap().view(dtype=np.uint8)
308 |
309 | output["_data_uint16"] = {
310 | "type": "xyz",
311 | "bounds": list(map(float, bounds_uint16)),
312 | "points": base64.b64encode(points_uint16).decode(),
313 | }
314 |
315 |
316 | def compress_laser_scan(msg, output):
317 | # compression scheme:
318 | # map ranges to _ranges_uint16 in the following format:
319 | # msg['_ranges_uint16'] = {
320 | # bounds: [ range_min, range_max ] (exclude nan/inf/-inf in min/max computation)
321 | # points: string: base64 encoded bytearray of struct uint16 r_frac
322 | # }
323 | # where r_frac = 0 reprents the minimum range, r_frac = 65534 maps to the max range, 65535 is invalid value (nan/-inf/inf)
324 | # msg['_intensities_uint16'] = {
325 | # ... same as above but for intensities ...
326 | # }
327 | # then set msg['ranges'] = [] and msg['intensities'] = []
328 |
329 | output["ranges"] = []
330 | output["intensities"] = []
331 | output["__comp"] = ["ranges", "intensities"]
332 |
333 | rpoints = np.array(msg.ranges, dtype = np.float32)
334 | ipoints = np.array(msg.intensities, dtype = np.float32)
335 |
336 | if len(ipoints) > 0 and len(ipoints) != len(rpoints):
337 | output["_error"] = "LaserScan error: intensities must be empty or equal in size to ranges"
338 | return
339 |
340 | bad_indexes = np.isnan(rpoints) | np.isinf(rpoints)
341 | rpoints[bad_indexes] = 0.0
342 | rpoints_good = rpoints[~bad_indexes]
343 |
344 | if len(rpoints_good) > 0:
345 | rmax = np.max(rpoints_good)
346 | rmin = np.min(rpoints_good)
347 | if rmax - rmin < 1.0:
348 | rmax = rmin + 1.0
349 |
350 | rpoints_uint16 = (65534 * (rpoints - rmin) / (rmax - rmin)).astype(np.uint16)
351 | rpoints_uint16[bad_indexes] = 65535
352 | else:
353 | rmax = 1.0
354 | rmin = 0.0
355 | rpoints_uint16 = 65535 * np.ones(rpoints.shape, dtype = np.uint16)
356 |
357 | if len(ipoints) > 0:
358 | imax = np.max(ipoints)
359 | imin = np.min(ipoints)
360 | if np.isnan(imax) or np.isinf(imax) or np.isnan(imin) or np.isinf(imin):
361 | imax = 1000.0
362 | imin = 0.0
363 | if imax - imin < 1.0:
364 | imax = imin + 1.0
365 | ipoints_uint16 = (65534 * (ipoints - imin) / (imax - imin)).astype(np.uint16)
366 | ipoints_uint16[bad_indexes] = 65535
367 | else:
368 | imax = 1.0
369 | imin = 0.0
370 | ipoints_uint16 = np.array([], dtype=np.uint16)
371 |
372 | if not np.little_endian:
373 | rpoints_uint16 = rpoints_uint16.byteswap()
374 | ipoints_uint16 = ipoints_uint16.byteswap()
375 |
376 | output["_ranges_uint16"] = {
377 | "type": "r",
378 | "bounds": [float(rmin), float(rmax)],
379 | "points": base64.b64encode(rpoints_uint16).decode(),
380 | }
381 |
382 | output["_intensities_uint16"] = {
383 | "type": "i",
384 | "bounds": [float(imin), float(imax)],
385 | "points": base64.b64encode(ipoints_uint16).decode(),
386 | }
387 |
--------------------------------------------------------------------------------