2 var ros = new ROSLIB.Ros();
4 var isDragging = false;
7 ros.connect('ws://'+robothostname+':9090');
10 ros.on('connection', function() {
11 information.alerts.push({message: "Connected to websocket server.", success: true});
14 ros.on('error', function(error) {
15 information.alerts.push({message: "Error connecting to websocket server.", danger: true});
18 ros.on('close', function() {
19 information.alerts.push({message: "Connection to websocket server closed.", info: true});
20 setTimeout(function() {
25 //tfClient.subscribe('base_link', function(tf) {
26 // var now = new Date();
27 // $("#pose").text(now.toLocaleTimeString() + ": (" + tf.translation.x + ", " + tf.translation.y + ")");
29 // robotMarker.x = tf.translation.x;
30 // robotMarker.y = -tf.translation.y;
31 // robotMarker.rotation = viewer2D.scene.rosQuaternionToGlobalTheta(tf.rotation);
33 var poseTopic = new ROSLIB.Topic({ros: ros, name: '/robot_pose', messageType: 'geometry_msgs/Pose'});
34 var sensorTopic = new ROSLIB.Topic({ros: ros, name: '/sensors', messageType: 'wild_thumper/Sensor'});
35 var batteryTopic = new ROSLIB.Topic({ros: ros, name: '/battery', messageType: 'sensor_msgs/BatteryState'});
36 var ledStripeTopic = new ROSLIB.Topic({ros: ros, name: '/led_stripe', messageType: 'wild_thumper/LedStripe'});
37 var cmdVelTopic = new ROSLIB.Topic({ros: ros, name: '/teleop/cmd_vel', messageType: 'geometry_msgs/Twist'});
39 poseTopic.subscribe(function(message) {
41 $("#pose").text(now.toLocaleTimeString() + ": (" + message.position.x + ", " + message.position.y + ")");
44 sensorTopic.subscribe(function(message) {
45 sensors.light = message.light;
46 sensors.temp = message.temp.toFixed(1);
47 sensors.humidity = message.humidity;
48 sensors.pressure = message.pressure.toFixed(1);
49 sensors.co = message.co;
52 batteryTopic.subscribe(function(message) {
53 power.voltage = message.voltage.toFixed(1);
54 power.current = message.current.toFixed(1);
57 viewer2D = new ROS2D.Viewer({
64 .bind('mousewheel', function(e) {
65 if (e.originalEvent.wheelDelta/120 > 0) {
66 viewer2D.scaleToDimensions(10, 10)
68 viewer2D.scaleToDimensions(5, 5)
71 .mousedown(function() {
73 mousePreX = undefined;
74 mousePreY = undefined;
79 .mousemove(function(event) {
81 if (mousePreX != undefined && mousePreY != undefined) {
82 var diffX = event.pageX - mousePreX;
83 var diffY = event.pageY - mousePreY;
84 console.log("Moving viewer2D by " + diffX + ", " + diffY);
85 viewer2D.shift(diffX, diffY);
87 mousePreX = event.pageX;
88 mousePreY = event.pageY;
92 // Setup the nav client.
93 NAV2D.OccupancyGridClientNav({
95 rootObject : viewer2D.scene,
97 serverName : '/move_base'
100 // Initialize the teleop.
101 teleop = new KEYBOARDTELEOP.Teleop({
103 topic : '/teleop/cmd_vel'
106 // Create a UI slider using JQuery UI.
107 $('#speed-slider').slider({
113 slide : function(event, ui) {
114 // Change the speed label.
115 speed_label.speed = ui.value;
117 teleop.scale = (ui.value * 2);
121 // Set the initial speed.
122 teleop.scale = ($('#speed-slider').slider('value') * 2);
127 front_row: ["[0]", "[1]", "[2]", "[3]"],
128 top_row: ["[7]", "[6]", "[5]", "[4]"],
129 aft_row: ["[8]", "[9]", "[10]", "[11]"],
130 bottom_left_row: ["[14]", "[15]"],
131 bottom_right_row: ["[13]", "[12]"],
134 $('.led_color').minicolors({
137 defaultValue: '#000000',
138 change: function(value) {
139 var rgb = $(this).minicolors('rgbObject');
140 var nums = jQuery.parseJSON($(this).prop("name"));
141 var msg = new ROSLIB.Message({
144 jQuery.each(nums, function(i, num) {
147 red: parseInt(rgb.r*127/255),
148 green: parseInt(rgb.g*127/255),
149 blue: parseInt(rgb.b*127/255)
152 ledStripeTopic.publish(msg);
156 function setSpeed(trans, rot) {
157 var msg = new ROSLIB.Message({
169 cmdVelTopic.publish(msg);
173 .bind('mousedown touchstart', function(e) {
176 .bind('mouseup touchend mouseleave', function(e) {
180 .bind('mousemove touchmove', function(e) {
182 // absolute click position
184 if (e.originalEvent.touches) {
185 X = e.originalEvent.touches[0].pageX;
186 Y = e.originalEvent.touches[0].pageY;
191 // relative click position
192 var Xrel = X - this.getBoundingClientRect().left - $(this).width()/2;
193 var Yrel = Y - this.getBoundingClientRect().top - $(this).height()/2;
195 var trans = -Yrel / ($(this).height()/2);
196 var rot = -Xrel / ($(this).width()/2);
197 setSpeed(trans*$("#scale_trans").val(), rot*$("#scale_rot").val());
201 information = new Vue({
207 classObject: function(id) {
209 "alert-success": this.alerts[id].success,
210 "alert-danger": this.alerts[id].danger,
211 "alert-info": this.alerts[id].info
219 data: {light: '', temp: '', humidity: '', pressure: '', co: ''}
230 speed_label = new Vue({
233 speed: $('#speed-slider').slider('value'),
237 $(".imagelink").on('click',function(){
239 $("img").attr("src", $("img").attr("src"))
242 $("input[type='number']").spinner();
243 $("#usb_cam").attr("src", "http://"+robothostname+":8080/stream?topic=/camera/color/image_raw");
246 Vue.component('input-value', {
247 template: '#input-value-template',
248 props: ['value', 'label', 'unit']
251 Vue.component('input-led', {
252 template: '#input-led-template',
253 props: ['name', 'label']