(!) 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.

Basic ROS functionality with roslibjs

Description: This tutorial shows you how to publish, subscribe, and perform service calls with roslibjs.

Keywords: roslibjs, web interface, teleoperation, Robot Web Tools

Tutorial Level: BEGINNER

Getting Started

This tutorial involves writing a single HTML file, which will contain the HTML and JavaScript needed to communicate with ROS over rosbridge. To begin, create a file simple.html with your favorite text editor.

The complete code for this tutorial can be found in the roslibjs repo.

The HTML Code

   1 <!DOCTYPE html>
   2 <html>
   3 <head>
   4 <meta charset="utf-8" />
   5 
   6 <script type="text/javascript" src="https://cdn.jsdelivr.net/npm/eventemitter2@6.4.9/lib/eventemitter2.min.js"></script>
   7 <script type="text/javascript" src="https://cdn.jsdelivr.net/npm/roslib@1/build/roslib.min.js"></script>
   8 
   9 <script type="text/javascript" type="text/javascript">
  10   // Connecting to ROS
  11   // -----------------
  12 
  13   var ros = new ROSLIB.Ros({
  14     url : 'ws://localhost:9090'
  15   });
  16 
  17   ros.on('connection', function() {
  18     console.log('Connected to websocket server.');
  19   });
  20 
  21   ros.on('error', function(error) {
  22     console.log('Error connecting to websocket server: ', error);
  23   });
  24 
  25   ros.on('close', function() {
  26     console.log('Connection to websocket server closed.');
  27   });
  28 
  29   // Publishing a Topic
  30   // ------------------
  31 
  32   var cmdVel = new ROSLIB.Topic({
  33     ros : ros,
  34     name : '/cmd_vel',
  35     messageType : 'geometry_msgs/Twist'
  36   });
  37 
  38   var twist = new ROSLIB.Message({
  39     linear : {
  40       x : 0.1,
  41       y : 0.2,
  42       z : 0.3
  43     },
  44     angular : {
  45       x : -0.1,
  46       y : -0.2,
  47       z : -0.3
  48     }
  49   });
  50   cmdVel.publish(twist);
  51 
  52   // Subscribing to a Topic
  53   // ----------------------
  54 
  55   var listener = new ROSLIB.Topic({
  56     ros : ros,
  57     name : '/listener',
  58     messageType : 'std_msgs/String'
  59   });
  60 
  61   listener.subscribe(function(message) {
  62     console.log('Received message on ' + listener.name + ': ' + message.data);
  63     listener.unsubscribe();
  64   });
  65 
  66   // Calling a service
  67   // -----------------
  68 
  69   var addTwoIntsClient = new ROSLIB.Service({
  70     ros : ros,
  71     name : '/add_two_ints',
  72     serviceType : 'rospy_tutorials/AddTwoInts'
  73   });
  74 
  75   var request = new ROSLIB.ServiceRequest({
  76     a : 1,
  77     b : 2
  78   });
  79 
  80   addTwoIntsClient.callService(request, function(result) {
  81     console.log('Result for service call on '
  82       + addTwoIntsClient.name
  83       + ': '
  84       + result.sum);
  85   });
  86 
  87   // Getting and setting a param value
  88   // ---------------------------------
  89 
  90   ros.getParams(function(params) {
  91     console.log(params);
  92   });
  93 
  94   var maxVelX = new ROSLIB.Param({
  95     ros : ros,
  96     name : 'max_vel_y'
  97   });
  98 
  99   maxVelX.set(0.8);
 100   maxVelX.get(function(value) {
 101     console.log('MAX VAL: ' + value);
 102   });
 103 </script>
 104 </head>
 105 
 106 <body>
 107   <h1>Simple roslib Example</h1>
 108   <p>Check your Web Console for output.</p>
 109 </body>
 110 </html>

Code Explanation

Now that we have an example, let's look at each piece.

   6 <script type="text/javascript" src="https://cdn.jsdelivr.net/npm/eventemitter2@6.4.9/lib/eventemitter2.min.js"></script>
   7 <script type="text/javascript" src="https://cdn.jsdelivr.net/npm/roslib@1/build/roslib.min.js"></script>

We first need to import all of the required JavaScript files for the application, including EventEmitter2 and roslibjs. Here, we use the Robot Web Tools CDN. The files can also be downloaded directly from their GitHub repos.

  13   var ros = new ROSLIB.Ros({
  14     url : 'ws://localhost:9090'
  15   });

Next, we need to create a Ros node object to communicate with a rosbridge v2.0 server. In this example, the script will connect to localhost on the default port of 9090.

The ROSLIB.Ros docs details ROSLIB.Ros constructor options and available functions.

  17   ros.on('connection', function() {
  18     console.log('Connected to websocket server.');
  19   });

This adds a listener for a connection event to the ros object. The two blocks following the connection event listener do the same for error and close events. This way, we can monitor the connection to the rosbridge server.

  32   var cmdVel = new ROSLIB.Topic({
  33     ros : ros,
  34     name : '/cmd_vel',
  35     messageType : 'geometry_msgs/Twist'
  36   });

A ROSLIB.Topic corresponds to a ROS Topic. The topic declares the topic name, message type, and passes in the ROS object from earlier. Topics can be used to subscribe or publish or both.

The ROSLIB.Topic docs contains information on ROSLIB.Topic functions.

  38   var twist = new ROSLIB.Message({
  39     linear : {
  40       x : 0.1,
  41       y : 0.2,
  42       z : 0.3
  43     },
  44     angular : {
  45       x : -0.1,
  46       y : -0.2,
  47       z : -0.3
  48     }
  49   });
  50   cmdVel.publish(twist);

To publish, we first need to create a new ROSLIB.Message. It takes in an object literal that matches up to the message definition on the ROS system. Nested objects are fine. See the ROSLIB.Message docs for available options when constructing a ROSLIB.Message object.

After we have the message, we just pass it to the ROSLIB.Topic to publish. If you followed the steps in Running the Example below, you can verify the message was published in the terminal by rostopic echo cmd_vel.

  55   var listener = new ROSLIB.Topic({
  56     ros : ros,
  57     name : '/listener',
  58     messageType : 'std_msgs/String'
  59   });
  60 
  61   listener.subscribe(function(message) {
  62     console.log('Received message on ' + listener.name + ': ' + message.data);
  63     listener.unsubscribe();
  64   });

The listener topic is created in the same fashion as the cmdVel topic above, accept it's dealing with the "/listener" topic name and "std_msgs/String" message type.

Subscribing happens by calling subscribe() on the topic and passing in a callback. Whenever ROS publishes a message on the "/listener" topic, rosbridge will forward that message to the browser and the callback function will be called with the message.

  69   var addTwoIntsClient = new ROSLIB.Service({
  70     ros : ros,
  71     name : '/add_two_ints',
  72     serviceType : 'rospy_tutorials/AddTwoInts'
  73   });

ROS services are also supported. First, we need to create a ROSLIB.Service object, which is similar to the ROSLIB.Topic object above in that it's responsible for all interactions with ROS services.

Check out the ROSLIB.Service docs for all ROSLIB.Service options.

  75   var request = new ROSLIB.ServiceRequest({
  76     a : 1,
  77     b : 2
  78   });
  79 
  80   addTwoIntsClient.callService(request, function(result) {
  81     console.log('Result for service call on '
  82       + addTwoIntsClient.name
  83       + ': '
  84       + result.sum);
  85   });

Like how a topic is called with a ROSLIB.Message object, a service is called with a ROSLIB.ServiceRequest.

The service is called on the service object with addTwoIntsClient.callService and passed two parameters: the ROSLIB.ServiceRequest and a callback function. The callback function will be called when the ROS service responds.

The ROSLIB.ServiceRequest docs and ROSLIB.ServiceResponse docs outline the available parameters for ROSLIB.ServiceRequest and ROSLIB.ServiceResponse objects.

  90   ros.getParams(function(params) {
  91     console.log(params);
  92   });
  93 
  94   var maxVelX = new ROSLIB.Param({
  95     ros : ros,
  96     name : 'max_vel_y'
  97   });
  98 
  99   maxVelX.set(0.8);
 100   maxVelX.get(function(value) {
 101     console.log('MAX VAL: ' + value);
 102   });

Getting and setting ROS params is also supported. Like ROSLIB.Topic and ROSLIB.ServiceROSLIB.Param` acts as the core object for dealing with a particular param.

Setting a param can be done with a simple param.set(value). Getting a param takes in a callback, which will be called when the server returns. Check out the ROSLIB.Param docs for available functions.

NOTE: Setting/Getting ROS Parameters requires a rosapi node to be running. See the discussion roslibjs#364.

Running the Example

At this point we are ready to run the example. To do so, you will need to have installed the following packages:

  • ros-hydro-ros-base (basic ROS installation)
  • ros-hydro-rosbridge-server (rosbridge_server)

  • ros-hydro-common-tutorials (Basic ROS tutorial package)
  • ros-hydro-rospy-tutorials (Rospy tutorial package)

To begin, we will launch ROS. To do so, run the following in a terminal:

  • roscore

Next, start publishing a message from the server to test our JavaScript subscriber:

  • rostopic pub /listener std_msgs/String "Hello, World"

Then start subscribing to a topic to test publishing from the browser:

  • rostopic echo /cmd_vel

Now run a service server that will return service calls from the browser:

  • rosrun rospy_tutorials add_two_ints_server

Once everything is running, we can launch the rosbridge v2.0 server with the following:

  • roslaunch rosbridge_server rosbridge_websocket.launch

Finally, you are now ready to bring up your HTML page in a web browser. You can open up the file directly in the browser without running a web server. The data outputted happens in the Web Console. Instructions to view the Web Console depends on the browser:

Wiki: roslibjs/Tutorials/BasicRosFunctionality (last edited 2023-10-18 22:17:12 by BenjaminBlumer)