2 var ros = new ROSLIB.Ros();
3 ros.connect('ws://wildthumper:9090');
4 var isDragging = false;
6 ros.on('connection', function() {
7 information.alerts.push({message: "Connected to websocket server.", success: true});
10 ros.on('error', function(error) {
11 information.alerts.push({message: "Error connecting to websocket server.", danger: true});
14 ros.on('close', function() {
15 information.alerts.push({message: "Connection to websocket server closed.", info: true});
18 //tfClient.subscribe('base_link', function(tf) {
19 // var now = new Date();
20 // $("#pose").text(now.toLocaleTimeString() + ": (" + tf.translation.x + ", " + tf.translation.y + ")");
22 // robotMarker.x = tf.translation.x;
23 // robotMarker.y = -tf.translation.y;
24 // robotMarker.rotation = viewer2D.scene.rosQuaternionToGlobalTheta(tf.rotation);
26 var poseTopic = new ROSLIB.Topic({ros: ros, name: '/robot_pose', messageType: 'geometry_msgs/Pose'});
27 var sensorTopic = new ROSLIB.Topic({ros: ros, name: '/sensors', messageType: 'wild_thumper/Sensor'});
28 var batteryTopic = new ROSLIB.Topic({ros: ros, name: '/battery', messageType: 'sensor_msgs/BatteryState'});
29 var ledStripeTopic = new ROSLIB.Topic({ros: ros, name: '/led_stripe', messageType: 'wild_thumper/LedStripe'});
30 var cmdVelTopic = new ROSLIB.Topic({ros: ros, name: '/teleop/cmd_vel', messageType: 'geometry_msgs/Twist'});
32 poseTopic.subscribe(function(message) {
34 $("#pose").text(now.toLocaleTimeString() + ": (" + message.position.x + ", " + message.position.y + ")");
37 sensorTopic.subscribe(function(message) {
38 sensors.light = message.light;
39 sensors.temp = message.temp.toFixed(1);
40 sensors.humidity = message.humidity;
41 sensors.pressure = message.pressure.toFixed(1);
42 sensors.co = message.co;
45 batteryTopic.subscribe(function(message) {
46 power.voltage = message.voltage.toFixed(1);
47 power.current = message.current.toFixed(1);
50 viewer2D = new ROS2D.Viewer({
57 .bind('mousewheel', function(e) {
58 if (e.originalEvent.wheelDelta/120 > 0) {
59 viewer2D.scaleToDimensions(10, 10)
61 viewer2D.scaleToDimensions(5, 5)
64 .mousedown(function() {
66 mousePreX = undefined;
67 mousePreY = undefined;
72 .mousemove(function(event) {
74 if (mousePreX != undefined && mousePreY != undefined) {
75 var diffX = event.pageX - mousePreX;
76 var diffY = event.pageY - mousePreY;
77 console.log("Moving viewer2D by " + diffX + ", " + diffY);
78 viewer2D.shift(diffX, diffY);
80 mousePreX = event.pageX;
81 mousePreY = event.pageY;
85 // Setup the nav client.
86 NAV2D.OccupancyGridClientNav({
88 rootObject : viewer2D.scene,
90 serverName : '/move_base'
93 // Initialize the teleop.
94 teleop = new KEYBOARDTELEOP.Teleop({
96 topic : '/teleop/cmd_vel'
99 // Create a UI slider using JQuery UI.
100 $('#speed-slider').slider({
106 slide : function(event, ui) {
107 // Change the speed label.
108 speed_label.speed = ui.value;
110 teleop.scale = (ui.value * 2);
114 // Set the initial speed.
115 teleop.scale = ($('#speed-slider').slider('value') * 2);
120 front_row: ["[0]", "[1]", "[2]", "[3]"],
121 top_row: ["[7]", "[6]", "[5]", "[4]"],
122 aft_row: ["[8]", "[9]", "[10]", "[11]"],
123 bottom_left_row: ["[14]", "[15]"],
124 bottom_right_row: ["[13]", "[12]"],
127 $('.led_color').minicolors({
130 defaultValue: '#000000',
131 change: function(value) {
132 var rgb = $(this).minicolors('rgbObject');
133 var nums = jQuery.parseJSON($(this).prop("name"));
134 var msg = new ROSLIB.Message({
137 jQuery.each(nums, function(i, num) {
140 red: parseInt(rgb.r*127/255),
141 green: parseInt(rgb.g*127/255),
142 blue: parseInt(rgb.b*127/255)
145 ledStripeTopic.publish(msg);
149 function setSpeed(trans, rot) {
150 var msg = new ROSLIB.Message({
162 cmdVelTopic.publish(msg);
166 .bind('mousedown touchstart', function(e) {
169 .bind('mouseup touchend mouseleave', function(e) {
173 .bind('mousemove touchmove', function(e) {
175 // absolute click position
177 if (e.originalEvent.touches) {
178 X = e.originalEvent.touches[0].pageX;
179 Y = e.originalEvent.touches[0].pageY;
184 // relative click position
185 var Xrel = X - this.offsetLeft - $(this).width()/2;
186 var Yrel = Y - this.offsetTop - $(this).height()/2;
188 var trans = -Yrel / ($(this).height()/2);
189 var rot = -Xrel / ($(this).width()/2);
190 setSpeed(trans, rot*3);
194 information = new Vue({
200 classObject: function(id) {
202 "alert-success": this.alerts[id].success,
203 "alert-danger": this.alerts[id].danger,
204 "alert-info": this.alerts[id].info
212 data: {light: '', temp: '', humidity: '', pressure: '', co: ''}
223 speed_label = new Vue({
226 speed: $('#speed-slider').slider('value'),
232 Vue.component('input-value', {
233 template: '#input-value-template',
234 props: ['value', 'label', 'unit']
237 Vue.component('input-led', {
238 template: '#input-led-template',
239 props: ['name', 'label']