|
<!DOCTYPE html> |
|
<html> |
|
|
|
<head> |
|
<link rel="stylesheet" href="https://cdnjs.cloudflare.com/ajax/libs/font-awesome/6.1.1/css/all.min.css" /> |
|
<link rel="stylesheet" href="https://www.w3schools.com/w3css/4/w3.css"> |
|
<link rel="stylesheet" href="https://uicdn.toast.com/chart/latest/toastui-chart.min.css" /> |
|
<script src="https://uicdn.toast.com/chart/latest/toastui-chart.min.js"></script> |
|
<meta name="viewport" content="width=device-width, initial-scale=1.0"> |
|
</head> |
|
|
|
<body class="w3-container"> |
|
<!-- Title bar --> |
|
<div class="w3-container w3-bar w3-card-4 w3-green w3-margin-bottom"> |
|
<h3 class="w3-bar-item">Zenoh teleop</h3> |
|
<!-- Battery percentage --> |
|
<h3 id="battery" class="w3-bar-item w3-right">Battery: - %</h3> |
|
</div> |
|
|
|
<div class="w3-row-padding"> |
|
<!-- Zenoh REST API URL input --> |
|
<div class="w3-third"> |
|
<label for="zenoh_rest_url">Zenoh REST URL</label> |
|
<input id="zenoh_rest_url" class="w3-input w3-border w3-padding-small" type="text" required |
|
value="http://demo.zenoh.iò:8000/"> |
|
</div> |
|
<!-- Subscriptions scope input --> |
|
<div class="w3-third"> |
|
<label>Subscriptions scope</label> |
|
<input id="sub_scope" class="w3-input w3-border w3-padding-small" type="text" value="simu"> |
|
</div> |
|
<div class="w3-third"> |
|
<label>.</label> |
|
<input type="submit" class="w3-btn w3-input w3-green w3-border w3-padding-small" value="Reset subscriptions" |
|
onclick="resetAllSubscriptions(); return false"><br /> |
|
</div> |
|
|
|
</div> |
|
|
|
<!-- Camera panel --> |
|
<div class="w3-card-4 w3-margin-bottom"> |
|
<header class="w3-bar w3-green" onclick="document.getElementById('Camera').classList.toggle('w3-hide');"> |
|
<h5 id="camera_title" class="w3-bar-item" style="margin: 0;">Camera</h5> |
|
<h5 class="w3-bar-item w3-right" style="margin: 0;"><i class='fa fa-video-camera'></i></h5> |
|
</header> |
|
<div id="Camera" class="w3-container w3-padding"> |
|
<img id="camera_img" class="w3-container w3-padding" style="max-width: 95%; max-height: 300px;" src="" /> |
|
</div> |
|
<br /> |
|
</div> |
|
|
|
<!-- Teleop panel --> |
|
<div class="w3-card-4 w3-margin-bottom"> |
|
<header class="w3-bar w3-green" onclick="document.getElementById('Drive').classList.toggle('w3-hide');"> |
|
<h5 class="w3-bar-item" style="margin: 0;">Drive</h5> |
|
<h5 class="w3-bar-item w3-right" style="margin: 0;"><i class='fa fa-gamepad'></i></h5> |
|
</header> |
|
<div id="Drive" class="w3-container w3-padding"> |
|
<div class="w3-container w3-cell"> |
|
<label for="twist_keyexpr">Pub Twists to:</label> |
|
</div> |
|
<div class="w3-container w3-cell"> |
|
<input id="twist_keyexpr" class="w3-input w3-border w3-padding-small" type="text" |
|
value="simu/rt/cmd_vel"> |
|
</div> |
|
<div class="w3-auto" style="display: grid; width:12em; height:9em; "> |
|
<button onmousedown="pubTwist(1.0, 0.0);" onmouseup="pubTwist(0.0, 0.0);" |
|
ontouchstart="pubTwist(1.0, 0.0);" ontouchend="pubTwist(0.0, 0.0);" |
|
style='font-size:2em; grid-column: 2; grid-row: 1;'> |
|
<i class='fas fa-caret-up'></i> |
|
</button> |
|
<button onmousedown="pubTwist(0.0, 1.0);" onmouseup="pubTwist(0.0, 0.0);" |
|
ontouchstart="pubTwist(0.0, 1.0);" ontouchend="pubTwist(0.0, 0.0);" |
|
style='font-size:2em; grid-column: 1; grid-row: 2;'> |
|
<i class='fas fa-caret-left'></i> |
|
</button> |
|
<button onmousedown="pubTwist(-1.0, 0.0);" onmouseup="pubTwist(0.0, 0.0);" |
|
ontouchstart="pubTwist(-1.0, 0.0);" ontouchend="pubTwist(0.0, 0.0);" |
|
style='font-size:2em; grid-column: 2; grid-row: 2;'> |
|
<i class='fas fa-caret-down'></i> |
|
</button> |
|
<button onmousedown="pubTwist(0.0, -1.0);" onmouseup="pubTwist(0.0, 0.0);" |
|
ontouchstart="pubTwist(0.0, -1.0);" ontouchend="pubTwist(0.0, 0.0);" |
|
style='font-size:2em; grid-column: 3; grid-row: 2;'> |
|
<i class='fas fa-caret-right'></i> |
|
</button> |
|
<button onclick="pubTwist(0.0, 0.0);" style='font-size:2em; grid-column: 1 / 4; grid-row: 3;'> |
|
STOP |
|
</button> |
|
</div> |
|
<br /> |
|
</div> |
|
</div> |
|
|
|
<!-- Lidar panel --> |
|
<div class="w3-card-4 w3-margin-bottom"> |
|
<header class="w3-bar w3-green" onclick="document.getElementById('Lidar').classList.toggle('w3-hide');"> |
|
<h5 id="lidar_title" class="w3-bar-item" style="margin: 0;">Lidar</h5> |
|
<h5 class="w3-bar-item w3-right" style="margin: 0;"><i class='fa fa-line-chart'></i></h5> |
|
</header> |
|
<div id="Lidar" class="w3-container w3-padding" style="width: 95%; height: 300px;"> |
|
</div> |
|
<br /> |
|
</div> |
|
|
|
<!-- rosout logs panel --> |
|
<div class="w3-card-4 w3-margin-bottom"> |
|
<header class="w3-bar w3-green" onclick="document.getElementById('Logs').classList.toggle('w3-hide');"> |
|
<h5 id="rosout_title" class="w3-bar-item" style="margin: 0;">Logs</h5> |
|
<h5 class="w3-bar-item w3-right" style="margin: 0;"><i class='fa fa-envelope'></i></h5> |
|
</header> |
|
<div id="Logs" class="w3-container w3-padding"> |
|
<div style="overflow:auto; height:200px; border:1px solid black;" id="rosout_logs"></div> |
|
</div> |
|
</div> |
|
|
|
<!-- Config panel --> |
|
<div class="w3-card-4 w3-margin-bottom"> |
|
<header class="w3-bar w3-green" onclick="document.getElementById('Config').classList.toggle('w3-hide');"> |
|
<h5 class="w3-bar-item" style="margin: 0;">Config</h5> |
|
<h5 class="w3-bar-item w3-right" style="margin: 0;"><i class='fa fa-gear'></i></h5> |
|
</header> |
|
<form id="Config" class="w3-container w3-hide"> |
|
<label for="linear_scale">Twists linear scale:</label> |
|
<input id="linear_scale" class="w3-input w3-border w3-padding-small" type="number" required |
|
value="0.12"><br /> |
|
<label for="angular_scale">Twists angular scale:</label> |
|
<input id="angular_scale" class="w3-input w3-border w3-padding-small" type="number" required |
|
value="1.0"><br /> |
|
<label for="scan_res">Subscribe to LaserScan from:</label> |
|
<input id="scan_res" class="w3-input w3-border w3-padding-small" type="text" required value="rt/scan"><br /> |
|
<label for="rosout_res">Subscribe to Log messages from:</label> |
|
<input id="rosout_res" class="w3-input w3-border w3-padding-small" type="text" required |
|
value="rt/rosout"><br /> |
|
<input type="submit" class="w3-btn w3-green" value="Reset subscriptions" |
|
onclick="resetAllSubscriptions(); return false"><br /> |
|
<br /> |
|
</form> |
|
</div> |
|
|
|
|
|
<script src="https://cdn.jsdelivr.net/npm/[email protected]"></script> |
|
<script src="https://cdn.jsdelivr.net/npm/[email protected]"></script> |
|
<script> |
|
// ROS2 Time type |
|
class Time { |
|
constructor(sec, nsec) { |
|
this.sec = sec; |
|
this.nsec = nsec; |
|
} |
|
|
|
static decode(cdrReader) { |
|
let sec = cdrReader.readInt32(); |
|
let nsec = cdrReader.readUint32(); |
|
return new Time(sec, nsec); |
|
} |
|
} |
|
|
|
// ROS2 Log type (received in 'rosout' topic) |
|
class Log { |
|
constructor(time, level, name, msg, file, fn, line) { |
|
this.time = time; |
|
this.level = level; |
|
this.name = name; |
|
this.msg = msg; |
|
this.file = file; |
|
this.fn = fn; |
|
this.line = line; |
|
} |
|
|
|
static decode(cdrReader) { |
|
let time = Time.decode(cdrReader); |
|
let level = cdrReader.readByte(); |
|
let name = cdrReader.readString(); |
|
let msg = cdrReader.readString(); |
|
let file = cdrReader.readString(); |
|
let fn = cdrReader.readString(); |
|
let line = cdrReader.readUint32(); |
|
return new Log(time, level, name, msg, file, fn, line); |
|
} |
|
} |
|
|
|
// ROS2 Vector3 type |
|
class Vector3 { |
|
constructor(x, y, z) { |
|
this.x = x; |
|
this.y = y; |
|
this.z = z; |
|
} |
|
|
|
encode(cdrWriter) { |
|
cdrWriter.writeFloat64(this.x); |
|
cdrWriter.writeFloat64(this.y); |
|
cdrWriter.writeFloat64(this.z); |
|
} |
|
|
|
static decode(cdrReader) { |
|
let x = cdrReader.readFloat64(); |
|
let y = cdrReader.readFloat64(); |
|
let z = cdrReader.readFloat64(); |
|
return new Vector3(x, y, z); |
|
} |
|
} |
|
|
|
// ROS2 Quaternion type |
|
class Quaternion { |
|
constructor(x, y, z, w) { |
|
this.x = x; |
|
this.y = y; |
|
this.z = z; |
|
this.w = w; |
|
} |
|
|
|
static decode(cdrReader) { |
|
let x = cdrReader.readFloat64(); |
|
let y = cdrReader.readFloat64(); |
|
let z = cdrReader.readFloat64(); |
|
let w = cdrReader.readFloat64(); |
|
return new Quaternion(x, y, z, w); |
|
} |
|
} |
|
|
|
// ROS2 Twist type (published in 'cmd_vel' topic) |
|
class Twist { |
|
constructor(linear, angular) { |
|
this.linear = linear; |
|
this.angular = angular; |
|
} |
|
|
|
encode(cdrWriter) { |
|
this.linear.encode(cdrWriter); |
|
this.angular.encode(cdrWriter); |
|
} |
|
} |
|
|
|
// ROS2 Header type |
|
class Header { |
|
constructor(time, frame_id) { |
|
this.time = time; |
|
this.frame_id = frame_id; |
|
} |
|
|
|
static decode(cdrReader) { |
|
let time = Time.decode(cdrReader); |
|
let frame_id = cdrReader.readString(); |
|
} |
|
} |
|
|
|
// ROS2 BatteryState type (received in 'battery_state' topic) |
|
// Warning: not complete, since we only need to decode up-to 'percentage' |
|
class BatteryState { |
|
constructor(header, voltage, temperature, current, charge, capacity, design_capacity, percentage) { |
|
this.header = header; |
|
this.voltage = voltage; |
|
this.temperature = temperature; |
|
this.current = current; |
|
this.charge = charge; |
|
this.capacity = capacity; |
|
this.design_capacity = design_capacity; |
|
this.percentage = percentage; |
|
} |
|
|
|
static decode(cdrReader) { |
|
let header = Header.decode(cdrReader); |
|
let voltage = cdrReader.readFloat32(); |
|
let temperature = cdrReader.readFloat32(); |
|
let current = cdrReader.readFloat32(); |
|
let charge = cdrReader.readFloat32(); |
|
let capacity = cdrReader.readFloat32(); |
|
let design_capacity = cdrReader.readFloat32(); |
|
let percentage = cdrReader.readFloat32(); |
|
return new BatteryState(header, voltage, temperature, current, charge, capacity, design_capacity, percentage); |
|
} |
|
} |
|
|
|
// LaserScan (Lidar publications) |
|
class LaserScan { |
|
constructor(header, angle_min, angle_max, angle_increment, time_increment, scan_time, range_min, range_max, ranges, intensities) { |
|
this.header = header; |
|
this.angle_min = angle_min; |
|
this.angle_max = angle_max; |
|
this.angle_increment = angle_increment; |
|
this.time_increment = time_increment; |
|
this.scan_time = scan_time; |
|
this.range_min = range_min; |
|
this.range_max = range_max; |
|
this.ranges = ranges; |
|
this.intensities = intensities; |
|
} |
|
|
|
static decode(cdrReader) { |
|
let header = Header.decode(cdrReader); |
|
let angle_min = cdrReader.readFloat32(); |
|
let angle_max = cdrReader.readFloat32(); |
|
let angle_increment = cdrReader.readFloat32(); |
|
let time_increment = cdrReader.readFloat32(); |
|
let scan_time = cdrReader.readFloat32(); |
|
let range_min = cdrReader.readFloat32(); |
|
let range_max = cdrReader.readFloat32(); |
|
|
|
let ranges_length = cdrReader.readInt32() |
|
let ranges = []; |
|
for (const x of Array(ranges_length).keys()) { |
|
ranges.push(cdrReader.readFloat32()) |
|
} |
|
|
|
let intensities_length = cdrReader.readInt32() |
|
let intensities = []; |
|
for (const x of Array(intensities_length).keys()) { |
|
intensities.push(cdrReader.readFloat32()) |
|
} |
|
return new LaserScan(header, angle_min, angle_max, angle_increment, time_increment, scan_time, range_min, range_max, ranges, intensities); |
|
} |
|
} |
|
|
|
const Http = new XMLHttpRequest(); |
|
|
|
function pubTwist(linear, angular) { |
|
// Get scales from HTML |
|
var linear_scale = document.getElementById("linear_scale").value |
|
var angular_scale = document.getElementById("angular_scale").value |
|
|
|
// Create a Twist message |
|
var twist = new Twist( |
|
new Vector3(linear * linear_scale, 0.0, 0.0), |
|
new Vector3(0.0, 0.0, angular * angular_scale)); |
|
console.log(twist); |
|
// Since it's going to DDS, encode it using a jscdr.CDRWriter |
|
var writer = new jscdr.CDRWriter(); |
|
twist.encode(writer); |
|
|
|
// Get bridge URL and twist_keyexpr resource to publish from HTML |
|
var bridge_url = document.getElementById("zenoh_rest_url").value |
|
var twist_keyexpr = document.getElementById("twist_keyexpr").value |
|
|
|
console.log("Send Twist to " + bridge_url + twist_keyexpr); |
|
// PUT it to zenoh via its REST API |
|
Http.open('PUT', bridge_url + twist_keyexpr, true); |
|
Http.setRequestHeader('Content-Type', 'application/octet-stream'); |
|
Http.send(writer.buf.buffer); |
|
} |
|
|
|
function onkeydown(e) { |
|
e = e || window.event; |
|
console.log("KeyPressed: " + e); |
|
if (e.keyCode == '38') { |
|
// up arrow |
|
pubTwist(1.0, 0.0); |
|
} |
|
else if (e.keyCode == '40') { |
|
// down arrow |
|
pubTwist(-1.0, 0.0); |
|
} |
|
else if (e.keyCode == '37') { |
|
// left arrow |
|
pubTwist(0.0, 1.0); |
|
} |
|
else if (e.keyCode == '39') { |
|
// right arrow |
|
pubTwist(0.0, -1.0); |
|
} |
|
else if (e.keyCode == '32') { |
|
// spacebar |
|
pubTwist(0.0, 0.0); |
|
} |
|
} |
|
|
|
function onkeyup(e) { |
|
// if key pressed was an arrow, send a Twist(0,0) to stop the robot |
|
if (e.keyCode == '37' || e.keyCode == '38' || e.keyCode == '39' || e.keyCode == '40') |
|
pubTwist(0.0, 0.0); |
|
} |
|
|
|
// register callback on key down |
|
document.onkeydown = onkeydown; |
|
// register callback on key up |
|
document.onkeyup = onkeyup; |
|
|
|
// EventSource receiving Logs |
|
var rosout_source = null; |
|
|
|
// subscribe to rosout topic |
|
function subscribeToRosout() { |
|
// close previous if exists |
|
if (rosout_source != null) { |
|
console.log("CLOSE ROSOUT EventSource"); |
|
rosout_source.close(); |
|
} |
|
|
|
if (typeof (EventSource) !== "undefined") { |
|
var zenoh_rest_url = document.getElementById("zenoh_rest_url").value |
|
var rosout_res = document.getElementById("rosout_res").value |
|
var scope = document.getElementById("sub_scope").value |
|
if (scope.length > 0 && !scope.endsWith("/")) { scope += "/" } |
|
console.log("Subscribe to EventSource: " + zenoh_rest_url + scope + rosout_res); |
|
rosout_source = new EventSource(zenoh_rest_url + scope + rosout_res); |
|
rosout_source.addEventListener("PUT", function (e) { |
|
console.log("Received sample: " + e.data); |
|
// The zenoh REST API sends JSON objects |
|
// that includes "key", "value", "encoding" and "time" (same than a result to GET) |
|
let sample = JSON.parse(e.data) |
|
// The payload buffer is in "value" field, encoded as base64. |
|
// Since it's comming from DDS, we decode it using a jscdr.CDRReader. |
|
let reader = new jscdr.CDRReader(dcodeIO.ByteBuffer.fromBase64(sample.value)); |
|
// Decode the buffer as a Log message |
|
let log = Log.decode(reader); |
|
// Add it to "rosout_logs" HTML element |
|
let elem = document.getElementById("rosout_logs"); |
|
elem.innerHTML += "[" + log.time.sec + "." + log.time.nsec + "] [" + log.name + "]: " + log.msg + "<br>"; |
|
// Auto-scroll to the bottom |
|
elem.scrollTop = elem.scrollHeight; |
|
}, false); |
|
|
|
// update panel title |
|
var title = document.getElementById("rosout_title"); |
|
title.innerHTML = "Logs: " + scope + rosout_res; |
|
|
|
} else { |
|
document.getElementById("rosout_logs").innerHTML = "Sorry, your browser does not support server-sent events..."; |
|
} |
|
} |
|
|
|
// EventSource receiving battery state |
|
var battery_source = null; |
|
|
|
// subscribe to battery_state topic |
|
function subscribeToBattery() { |
|
// close previous if exists |
|
if (battery_source != null) { |
|
console.log("CLOSE Battery EventSource"); |
|
battery_source.close(); |
|
} |
|
|
|
if (typeof (EventSource) !== "undefined") { |
|
var zenoh_rest_url = document.getElementById("zenoh_rest_url").value |
|
// battery_state key is the same than rousout key but replacing "rosout" with "battery_state" |
|
var battery_key = document.getElementById("rosout_res").value.replace("rosout", "battery_state") |
|
var scope = document.getElementById("sub_scope").value |
|
if (scope.length > 0 && !scope.endsWith("/")) { scope += "/" } |
|
console.log("Subscribe to EventSource: " + zenoh_rest_url + scope + battery_key); |
|
battery_source = new EventSource(zenoh_rest_url + scope + battery_key); |
|
battery_source.addEventListener("PUT", function (e) { |
|
console.log("Received sample: " + e.data); |
|
// The zenoh REST API sends JSON objects |
|
// that includes "key", "value", "encoding" and "time" (same than a result to GET) |
|
let sample = JSON.parse(e.data) |
|
// The payload buffer is in "value" field, encoded as base64. |
|
// Since it's comming from DDS, we decode it using a jscdr.CDRReader. |
|
let reader = new jscdr.CDRReader(dcodeIO.ByteBuffer.fromBase64(sample.value)); |
|
// Decode the buffer as a BatteryState message |
|
let battery = BatteryState.decode(reader); |
|
// Set it to "battery" HTML element |
|
let elem = document.getElementById("battery"); |
|
elem.innerHTML = "Battery: " + Math.round(battery.percentage) + " %"; |
|
}, false); |
|
|
|
} else { |
|
document.getElementById("rosout_logs").innerHTML = "Sorry, your browser does not support server-sent events..."; |
|
} |
|
} |
|
|
|
// Setup Chart for Lidar display |
|
data = { |
|
categories: [], |
|
series: [ |
|
{ |
|
data: [] |
|
}, |
|
], |
|
}; |
|
chart = toastui.Chart.radarChart({ |
|
el: document.getElementById("Lidar"), |
|
data, |
|
options: { |
|
chart: { height: 'auto', width: 'auto', animation: false }, |
|
plot: { type: 'circle' }, |
|
verticalAxis: { scale: { max: 3 } }, |
|
legend: { visible: false }, |
|
exportMenu: { visible: false }, |
|
tooltip: { template: () => `` }, |
|
series: { |
|
selectable: false, |
|
showDot: true, |
|
showArea: true, |
|
}, |
|
theme: { |
|
series: { lineWidth: 0.00001 }, |
|
verticalAxis: { |
|
label: { fontSize: 0, }, |
|
}, |
|
}, |
|
} |
|
}); |
|
|
|
// EventSource receiving LaserScan |
|
var scan_source = null; |
|
|
|
function subscribeToScan() { |
|
// close previous if exists |
|
if (scan_source != null) { |
|
console.log("CLOSE Scan EventSource"); |
|
scan_source.close(); |
|
} |
|
|
|
if (typeof (EventSource) !== "undefined") { |
|
var zenoh_rest_url = document.getElementById("zenoh_rest_url").value |
|
var scan_res = document.getElementById("scan_res").value |
|
var scope = document.getElementById("sub_scope").value |
|
if (scope.length > 0 && !scope.endsWith("/")) { scope += "/" } |
|
console.log("Subscribe to EventSource: " + zenoh_rest_url + scope + scan_res); |
|
scan_source = new EventSource(zenoh_rest_url + scope + scan_res); |
|
scan_source.addEventListener("PUT", function (e) { |
|
let sample = JSON.parse(e.data); |
|
// The payload buffer is in "value" field, encoded as base64. |
|
// Since it's comming from DDS, we decode it using a jscdr.CDRReader. |
|
let reader = new jscdr.CDRReader(dcodeIO.ByteBuffer.fromBase64(sample.value)); |
|
// Decode the buffer as an LaserScan message |
|
let scan = LaserScan.decode(reader); |
|
|
|
data.categories = []; |
|
data.series[0].data = []; |
|
chart.setData(data); |
|
data.categories = Array(scan.ranges.length).fill(''); |
|
data.series[0].data = scan.ranges.reverse(); |
|
chart.setData(data); |
|
|
|
}, false); |
|
|
|
// update panel title |
|
var title = document.getElementById("lidar_title"); |
|
title.innerHTML = "Lidar: " + scope + scan_res; |
|
|
|
} else { |
|
document.document.getElementById("Lidar").innerHTML = "Sorry, your browser does not support server-sent events..."; |
|
} |
|
} |
|
|
|
|
|
function setCameraSrc() { |
|
// If your robot has a camera and zcapture installed (from zenoh-demos/computer-vision/zcam/), |
|
// uncomment the camera <div> block on top of this file. |
|
// The zcapture must be started with "-k <scope>/cams/0", and the zenoh router must have the WebServer plugin running |
|
if (document.getElementById("camera_img") != null) { |
|
// Set "camera_img" element's src to the same URL host, but with port 8080 (WebServer plugin) |
|
// and with path: "demo/zcam?_method=SUB" |
|
var zenoh_rest_url = document.getElementById("zenoh_rest_url").value |
|
var scope = document.getElementById("sub_scope").value |
|
if (scope.length > 0 && !scope.endsWith("/")) { scope += "/" } |
|
img_url = zenoh_rest_url.replace(":8000", ":8080") + scope + "cams/0?_method=SUB"; |
|
document.getElementById("camera_img").src = img_url; |
|
|
|
// update panel title |
|
var title = document.getElementById("camera_title"); |
|
title.innerHTML = "Camera: " + scope + "cams/0"; |
|
} |
|
} |
|
|
|
function resetAllSubscriptions() { |
|
subscribeToBattery(); |
|
subscribeToRosout(); |
|
subscribeToScan(); |
|
setCameraSrc(); |
|
} |
|
|
|
// Get "host" and "scope" from URL params, and set "zenoh_rest_url" and "scope" accordingly |
|
const urlParams = new URLSearchParams(window.location.search); |
|
const host = urlParams.get('host') |
|
if (host != null && host.length > 0) { |
|
console.log("host: " + host); |
|
document.getElementById("zenoh_rest_url").value = "http://" + host + "/"; |
|
} |
|
const scope = urlParams.get('scope') |
|
if (host != null && host.length > 0) { |
|
console.log("scope: " + scope); |
|
document.getElementById("scope").value = scope; |
|
} |
|
|
|
// subscribe at page loading |
|
resetAllSubscriptions(); |
|
</script> |
|
|
|
<script type="text/javascript"> |
|
</script> |
|
|
|
</body> |
|
|
|
</html> |