!

Note: This tutorial assumes that you have completed the previous tutorials: Running Rosbridge.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Publishing video and IMU messages with roslibjs

Description: This tutorial shows you how to use a mobile phone to publish video and IMU messages via roslibjs and rosbridge

Keywords: roslibjs, rosbridge, imu, camera, video

Tutorial Level: BEGINNER

Getting Started

This tutorial involves writing a single HTML file, which will contain the HTML and JavaScript needed to run a camera and gyro on a phone and publish it to ROS over rosbridge. This gives you a basic video stream and IMU for your robot, just by putting a mobile phone on the robot.

All you need to do is create a file camera.html with your favorite text editor and make it accessible via a webserver running on the server that is running the rosbridge. Once the client is running on your phone, you can subscribe to its messages, for example using the "image" or "imu" displays available in RViz.

Note that this has been tested with Chrome on an Android phone and a Windows PC: not all browsers support the javascript DeviceOrientationEvent class or the getUserMedia() method.

The HTML Code

   1 <!DOCTYPE html>
   2 <html>
   3 <head>
   4 <script src="http://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
   5 <script src="http://static.robotwebtools.org/roslibjs/current/roslib.min.js"></script>
   6 <script src="http://cdnjs.cloudflare.com/ajax/libs/three.js/r71/three.min.js"></script>
   7 <script>
   8 // these two lines contain the base64-encoded images to turn on- and off the application.
   9       var RECORD_ON ="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAADIAAAAyCAMAAAAp4XiDAAAASFBMVEUAAAAAAADMzMz/AABmZmaZmZnMAABmAACZAAAzAAAzMzP/MzPMZmaZMzPMMzP/MwD/////Zmb/ZgBmMzPMmZmZZmb/mQD/mZlxvxKlAAAAAXRSTlMAQObYZgAAAAFiS0dEAIgFHUgAAAAJcEhZcwAACxMAAAsTAQCanBgAAAAHdElNRQffCBIMMyVTqZicAAACK0lEQVRIx43W63aDIAwA4KJJhVjrVtfu/d90kASIFlzzp5fDd5KAgJdLJwa8fB6YYojBXz4EQw1EgNPxAGDHqzpDBqDV0EN5DDoToIhagkSAOwb2DIEBRLEWINJf2DQspCQ7AwiUy0M69pEFyCR/xZCl4cTE/CgQtYoU2xZC2J6YiXNHA3ai4uApRwjaj+RBs+JWpKHLcrstiyAz3WjFUFJMk4/jf39+fqPyCdXJLmmwzi4L7+8a8avPhlwtzSQRcY0x3+9z+mSz8bSY0jRJWoEirtdxlM+IluczEXA7In+FbVm8jJ9jqIpmC2nBSjc6XXFZwvS83XwC4/wdI5pRDLczUE6TSJoPisRrDhNCkqFSmTY/pN6ZpIo05pguGZk1qawSKL3PxnznNIGHkDSjK1/q4tZNnlFI0CdNCeiTooRjXVfTTV5PJnggWTxejzNCDfJ6PdYWGd6zXHOWR7ewXi/jOrYJ8PbCvFH8cSGFlBmjQoZC/Dup68LbjAmWR39fWaOu1MRFCNg0rWesrCQTU1njuaxPZW1lX1neYRXwvgy1rkLQGN2WZVOWJHFPDZBPMUTXMVZAvZ+gnolqfBlvT6VEymGJelzryedL7M4+MFdTvIwAnDn8JnPCupbgO7KaeijHLz1xNKzseBVweTPketEQQgDagLAhssFWIl6P5j3OpK5QzgB8lXVufiFoFkl/n71fZIPlDeYsxa64+l7yH1BFUAv6ANgZ7wz/A295IO9de7kCAAAAAElFTkSuQmCC";
  10       var RECORD_OFF = "data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAADIAAAAyBAMAAADsEZWCAAAAFVBMVEVvcm0AAAAzMzNmZmbMzMyZmZn///8pcdebAAAAAXRSTlMAQObYZgAAAAFiS0dEAIgFHUgAAAAJcEhZcwAACxMAAAsTAQCanBgAAAAHdElNRQffCBINBR5qfIr6AAABv0lEQVQ4y22UQZaCMAyGffo8QED3Q9E9EDmAYzrrgZIbzJv7H2GStFLLmA22H/+fWNLsdi/hd2+DeSHP/A6Qhg9duX/AhVJskAGPoyLsNmACjVrQkMFe3u0hxUKPj5W0BqoWh0YeSxbtb2o1xvyNGPqnCMkLYPr6/SEOABcKqeKbF8mV2UE1KgHysbyDStaQTCKKR8GpYHDoIJVuJ3hcyJZVK1ZanFbuv5XQIypaRBycoupkdkx3kzhBg3NOMl2j3UJ9LS+6NRCufSLyq9KtqBFVPWmi4+KBoUbZkQoUiMHniZTcYYYqmylpjUgBdyVohu2s5HxOpDdiSWbNA3UlZR/lBBqw/CYyIkenRL9ZqjfVFgln0vJckiaTkIkvNYXba57WZRLku03xPHPo2sj9DamVLFuiFZ2pE2IfbkNOQnY32hBdXrR7RoLSzhrhYWQqRNYj/NB281MhsrZiVGJtuYpiw7E16RiajGIrYrxdGHooo0ZMdxQ3BJ8XErHfSrrnxcamlOB65Qu/K+bbLWTOXrxKDKU/JU3I/DoQDsjMgwmYyyFyGNkGj4ykgOXgET8bSf+AqAZ1DIhvBhwivu7/ATYxlvOTH50RAAAAAElFTkSuQmCC";
  11 
  12       var alpha, valpha, z;
  13       var beta, vbeta, x;
  14       var gamma, vgamma, y;
  15 
  16       var cameraTimer, imuTimer;
  17 
  18 // setup event handler to capture the orientation event and store the most recent data in a variable
  19 
  20       if (window.DeviceOrientationEvent) {
  21         // Listen for the deviceorientation event and handle the raw data
  22         window.addEventListener('deviceorientation', function(eventData) {
  23           // gamma is the left-to-right tilt in degrees, where right is positive
  24           gamma = eventData.gamma;
  25           
  26           // beta is the front-to-back tilt in degrees, where front is positive
  27           beta = eventData.beta;
  28           
  29           // alpha is the compass direction the device is facing in degrees
  30           alpha = eventData.alpha
  31 
  32           }, false);
  33         };
  34 
  35 // setup event handler to capture the acceleration event and store the most recent data in a variable
  36 
  37         if (window.DeviceMotionEvent) {
  38           window.addEventListener('devicemotion', deviceMotionHandler, false);
  39         } else {
  40           window.alert("acceleration measurements Not supported.");
  41         }
  42 
  43         function deviceMotionHandler(eventData) {
  44           // Grab the acceleration from the results
  45           var acceleration = eventData.acceleration;
  46           x = acceleration.x;
  47           y = acceleration.y;
  48           z = acceleration.z;
  49 
  50           // Grab the rotation rate from the results
  51           var rotation = eventData.rotationRate;
  52           vgamma = rotation.gamma;  
  53           vbeta = rotation.beta;
  54           valpha = rotation.alpha;
  55 }
  56 
  57 
  58 // setup connection to the ROS server and prepare the topic
  59   var ros = new ROSLIB.Ros();
  60 
  61   ros.on('connection', function() { console.log('Connected to websocket server.');});
  62 
  63   ros.on('error', function(error) { console.log('Error connecting to websocket server: ', error); window.alert('Error connecting to websocket server'); });
  64 
  65   ros.on('close', function() { console.log('Connection to websocket server closed.');});
  66 
  67   var imageTopic = new ROSLIB.Topic({
  68     ros : ros,
  69     name : '/camera/image/compressed',
  70     messageType : 'sensor_msgs/CompressedImage'
  71   });
  72 
  73   var imuTopic = new ROSLIB.Topic({
  74     ros : ros,
  75     name : '/gyro',
  76     messageType : 'sensor_msgs/Imu'
  77   });
  78 </script>
  79 </head>
  80 
  81 <!-- declare interface and the canvases that will display the video and the still shots -->
  82 <body>
  83  <video style="display: none" autoplay id="video"></video>
  84  <canvas style="display: none" id="canvas"></canvas>
  85  <button id="startstop" style="outline-width: 0; background-color: transparent; border: none"><img id="startstopicon" src=""/></button>
  86 
  87 <script>
  88 
  89       document.getElementById('startstopicon').setAttribute('src', RECORD_OFF);
  90 
  91 // request access to the video camera and start the video stream
  92   var hasRunOnce = false,
  93       video        = document.querySelector('#video'),
  94       canvas       = document.querySelector('#canvas'),
  95       width = 640,
  96       height,           // calculated once video stream size is known
  97       cameraStream;
  98 
  99 
 100   function cameraOn() {
 101           navigator.getMedia = ( navigator.getUserMedia ||
 102                                  navigator.webkitGetUserMedia ||
 103                                  navigator.mozGetUserMedia ||
 104                                  navigator.msGetUserMedia);
 105 
 106           navigator.getMedia(
 107             {
 108               video: true,
 109               audio: false
 110             },
 111             function(stream) {
 112               cameraStream = stream;
 113               if (navigator.mozGetUserMedia) {
 114                 video.mozSrcObject = stream;
 115               } else {
 116                 var vendorURL = window.URL || window.webkitURL;
 117                 video.src = vendorURL.createObjectURL(stream);
 118               }
 119               video.play();
 120             },
 121             function(err) {
 122               console.log("An error occured! " + err);
 123               window.alert("An error occured! " + err);
 124             }
 125           );
 126   }
 127 
 128 
 129   function cameraOff() {
 130         cameraStream.stop();
 131         hasRunOnce = false;
 132         takepicture();                  // blank the screen to prevent last image from staying
 133     }
 134 
 135 // function that is run once scale the height of the video stream to match the configured target width
 136   video.addEventListener('canplay', function(ev){
 137     if (!hasRunOnce) {
 138       height = video.videoHeight / (video.videoWidth/width);
 139       video.setAttribute('width', width);
 140       video.setAttribute('height', height);
 141       canvas.setAttribute('width', width);
 142       canvas.setAttribute('height', height);
 143       hasRunOnce = true;
 144     }
 145   }, false);
 146 
 147 // function that is run by trigger several times a second
 148 // takes snapshot of video to canvas, encodes the images as base 64 and sends it to the ROS topic
 149   function takepicture() {
 150     canvas.width = width;
 151     canvas.height = height;
 152 
 153     canvas.getContext('2d').drawImage(video, 0, 0, canvas.width, canvas.height);   
 154  
 155     var data = canvas.toDataURL('image/jpeg');
 156     var imageMessage = new ROSLIB.Message({
 157         format : "jpeg",
 158         data : data.replace("data:image/jpeg;base64,", "")
 159     });
 160 
 161     imageTopic.publish(imageMessage);
 162   }
 163 
 164  function imusnapshot() {
 165      var beta_radian = ((beta + 360) / 360 * 2 * Math.PI) % (2 * Math.PI);
 166      var gamma_radian = ((gamma + 360) / 360 * 2 * Math.PI) % (2 * Math.PI);
 167      var alpha_radian = ((alpha + 360) / 360 * 2 * Math.PI) % (2 * Math.PI);
 168      var eurlerpose = new THREE.Euler(beta_radian, gamma_radian, alpha_radian);
 169      var quaternionpose = new THREE.Quaternion;
 170      quaternionpose.setFromEuler(eurlerpose);
 171 
 172      var imuMessage = new ROSLIB.Message({
 173         header : {
 174            frame_id : "world"
 175         },
 176         orientation : {
 177            x : quaternionpose.x,
 178            y : quaternionpose.y,
 179            z : quaternionpose.z,
 180            w : quaternionpose.w
 181         },
 182         orientation_covariance : [0,0,0,0,0,0,0,0,0],
 183         angular_velocity : {
 184            x : vbeta,
 185            y : vgamma,
 186            z : valpha,
 187         },
 188         angular_velocity_covariance  : [0,0,0,0,0,0,0,0,0],
 189         linear_acceleration : {
 190            x : x,
 191            y : y,
 192            z : z,
 193         },
 194         linear_acceleration_covariance  : [0,0,0,0,0,0,0,0,0],
 195      });
 196 
 197      imuTopic.publish(imuMessage);
 198   }
 199 // turning on and off the timer that triggers sending pictures and imu information several times a second
 200   startstopicon.addEventListener('click', function(ev){
 201       if(cameraTimer == null) {
 202           ros.connect("ws://" + window.location.hostname + ":9090");
 203           cameraOn();
 204           cameraTimer = setInterval(function(){
 205                 takepicture();
 206            }, 250);       // publish an image 4 times per second
 207           imuTimer = setInterval(function(){
 208                 imusnapshot();
 209            }, 100);       // publish an IMU message 10 times per second
 210            document.getElementById('startstopicon').setAttribute('src', RECORD_ON);
 211        } else {
 212            ros.close();
 213            cameraOff();
 214            clearInterval(cameraTimer);
 215            clearInterval(imuTimer);
 216            document.getElementById('startstopicon').setAttribute('src', RECORD_OFF);
 217            cameraTimer = null;
 218            imuTimer = null;
 219        }
 220   }, false);
 221 </script>
 222 </body>
 223 </html>

Code Explanation

Now that we have an example, let's look at some of the more important parts. This is where the topic names are defined.

  67   var imageTopic = new ROSLIB.Topic({
  68     ros : ros,
  69     name : '/camera/image/compressed',
  70     messageType : 'sensor_msgs/CompressedImage'
  71   });
  72 
  73   var imuTopic = new ROSLIB.Topic({
  74     ros : ros,
  75     name : '/gyro',
  76     messageType : 'sensor_msgs/Imu'

This is where the size of the published image is configured.

  95       width = 640,

Take a snapshot of the canvas showing the video capture, and store it as a base-64 encoded string (a "data URI"). Then strip away the URI part so that only the image remains, and publish that.

 153     canvas.getContext('2d').drawImage(video, 0, 0, canvas.width, canvas.height);   
 154  
 155     var data = canvas.toDataURL('image/jpeg');
 156     var imageMessage = new ROSLIB.Message({
 157         format : "jpeg",
 158         data : data.replace("data:image/jpeg;base64,", "")

This is where the target frame is configured. Define a frame for your robot depending on where you attach the phone, and configure the target here. By default the "world" frame is used.

 172      var imuMessage = new ROSLIB.Message({
 173         header : {
 174            frame_id : "world"
 175         },

This is where the frequency of publishing is configured. By setting to 250 we publish every 250 milliseconds, or 4 times per second.

 200   startstopicon.addEventListener('click', function(ev){
 201       if(cameraTimer == null) {
 202           ros.connect("ws://" + window.location.hostname + ":9090");
 203           cameraOn();
 204           cameraTimer = setInterval(function(){
 205                 takepicture();
 206            }, 250);       // publish an image 4 times per second
 207           imuTimer = setInterval(function(){
 208                 imusnapshot();
 209            }, 100);       // publish an IMU message 10 times per second
 210 

Wiki: roslibjs/Tutorials/Publishing video and IMU data with roslibjs (last edited 2020-01-25 06:41:38 by JashMota)