控制台结果输出效果:
话题结构:
html部分
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />
<script type="text/javascript" src="http://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
<script type="text/javascript" src="http://static.robotwebtools.org/roslibjs/current/roslib.min.js"></script>
<script type="text/javascript" type="text/javascript">
//连接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.');
});
// 发布一个话题
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);
// 订阅一个话题
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);
});
// 获取和设置一个参数值
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>
ros部分(前提是安装过ros以及rosbridge_server等;详情见官方文档)
roscore
rostopic pub /listener std_msgs/String "Hello, World"
rostopic echo /cmd_vel
rosrun rospy_tutorials add_two_ints_server
roslaunch rosbridge_server rosbridge_websocket.launch
roslib案例官方文档 http://wiki.ros.org/roslibjs/Tutorials/BasicRosFunctionality#Running_the_Example