< >
Home » ROS与JS入门教程 » ROS与javascript入门教程-roslibjs-基本功能

ROS与javascript入门教程-roslibjs-基本功能

ROS与javascript入门教程-roslibjs-基本功能

说明:

  • 介绍如何利用roslibjs库发布话题,订阅话题,调用服务

github:

完整代码:

  • 新建名称为simple.html

  • 内容为:

<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />

<script type="text/javascript" src="http://cdn.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
<script type="text/javascript" src="http://cdn.robotwebtools.org/roslibjs/current/roslib.min.js"></script>

<script type="text/javascript" type="text/javascript">
  // Connecting to ROS
  // -----------------

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

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

  ros.on('error', function(error) {
    console.log('Error connecting to websocket server: ', error);
  });

  ros.on('close', function() {
    console.log('Connection to websocket server closed.');
  });

  // Publishing a Topic
  // ------------------

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

  var twist = new ROSLIB.Message({
    linear : {
      x : 0.1,
      y : 0.2,
      z : 0.3
    },
    angular : {
      x : -0.1,
      y : -0.2,
      z : -0.3
    }
  });
  cmdVel.publish(twist);

  // Subscribing to a Topic
  // ----------------------

  var listener = new ROSLIB.Topic({
    ros : ros,
    name : '/listener',
    messageType : 'std_msgs/String'
  });

  listener.subscribe(function(message) {
    console.log('Received message on ' + listener.name + ': ' + message.data);
    listener.unsubscribe();
  });

  // Calling a service
  // -----------------

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

  var request = new ROSLIB.ServiceRequest({
    a : 1,
    b : 2
  });

  addTwoIntsClient.callService(request, function(result) {
    console.log('Result for service call on '
      + addTwoIntsClient.name
      + ': '
      + result.sum);
  });

  // Getting and setting a param value
  // ---------------------------------

  ros.getParams(function(params) {
    console.log(params);
  });

  var maxVelX = new ROSLIB.Param({
    ros : ros,
    name : 'max_vel_y'
  });

  maxVelX.set(0.8);
  maxVelX.get(function(value) {
    console.log('MAX VAL: ' + value);
  });
</script>
</head>

<body>
  <h1>Simple roslib Example</h1>
  <p>Check your Web Console for output.</p>
</body>
</html>

代码解析:

  • 代码段:
<script type="text/javascript" src="http://cdn.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
<script type="text/javascript" src="http://cdn.robotwebtools.org/roslibjs/current/roslib.min.js"></script>
  • 解释:首先加载需要的核心脚本库eventemitter2和roslib

  • 代码端:

var ros = new ROSLIB.Ros({
   url : 'ws://localhost:9090'
});
  • 解释:

    • 创建Ros节点连接到rosbridge v2.0 server
    • 指定ROS服务器IP地址和端口号
    • 更多ROSLIB.Ros文档可以参考:http://robotwebtools.org/jsdoc/roslibjs/current/
  • 代码段:

ros.on('connection', function() {
   console.log('Connected to websocket server.');
});
  • 解释:增加监听事件,如果连接上打印已经连接的信息

  • 代码段:

var cmdVel = new ROSLIB.Topic({
   ros : ros,
   name : '/cmd_vel',
   messageType : 'geometry_msgs/Twist'
});
  • 解释:

    • 创建话题
    • 更多ROSLIB.Topic文档:http://robotwebtools.org/jsdoc/roslibjs/current/
  • 代码段:

 var twist = new ROSLIB.Message({
    linear : {
      x : 0.1,
      y : 0.2,
      z : 0.3
    },
    angular : {
      x : -0.1,
      y : -0.2,
      z : -0.3
    }
  });
  cmdVel.publish(twist);
  • 解释:

    • 创建消息内容并发布
    • 更多ROSLIB.Message文档:http://robotwebtools.org/jsdoc/roslibjs/current/
  • 代码段:

  var listener = new ROSLIB.Topic({
    ros : ros,
    name : '/listener',
    messageType : 'std_msgs/String'
  });

  listener.subscribe(function(message) {
    console.log('Received message on ' + listener.name + ': ' + message.data);
    listener.unsubscribe();
  });
  • 解释:
    • 创建订阅话题,获取内容后打印
    • 与发布话题不同,这里提供一个回调函数处理获取的内容
  • 代码段:
  var addTwoIntsClient = new ROSLIB.Service({
    ros : ros,
    name : '/add_two_ints',
    serviceType : 'rospy_tutorials/AddTwoInts'
  });
  • 解释:
    • 创建服务对象
    • 更多ROSLIB.Service文档:http://robotwebtools.org/jsdoc/roslibjs/current/
  • 代码段:
  var request = new ROSLIB.ServiceRequest({
    a : 1,
    b : 2
  });

  addTwoIntsClient.callService(request, function(result) {
    console.log('Result for service call on '
      + addTwoIntsClient.name
      + ': '
      + result.sum);
  });
  • 解释:

    • 创建请求对象
    • 调用服务,通过回调函数打印结果
  • 代码段:

  ros.getParams(function(params) {
    console.log(params);
  });

  var maxVelX = new ROSLIB.Param({
    ros : ros,
    name : 'max_vel_y'
  });

  maxVelX.set(0.8);
  maxVelX.get(function(value) {
    console.log('MAX VAL: ' + value);
  });
  • 解释:
    • 单独获取参数
    • 创建参数对象,设置和获取参数

运行

  • 安装相应的包:
sudo apt-get install ros-kinetic-ros-base
sudo apt-get install ros-kinetic-common-tutorials
sudo apt-get install ros-kinetic-rospy-tutorials 
sudo apt-get install ros-kinetic-rosbridge-server
  • 服务器端,新终端,运行:
roslaunch rosbridge_server rosbridge_websocket.launch
  • 效果图:

请输入图片描述

  • 服务器端,新终端,运行:
rostopic pub /listener std_msgs/String "Hello, World"
  • 服务器端,新终端,运行:
rostopic echo /cmd_vel
  • 服务器端,新终端,运行:
rosrun rospy_tutorials add_two_ints_server
  • 测试的网页通过浏览器上运行:
http://127.0.0.1/simple.html
  • 或者直接拖动文件到浏览器
file://simple.html
  • 效果图:

请输入图片描述

参考:

  • http://wiki.ros.org/roslibjs/Tutorials/BasicRosFunctionality

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros与javascript入门教程