forked from RobotWebTools/roslibjs
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathsimple.html
125 lines (112 loc) · 3.46 KB
/
simple.html
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
<!DOCTYPE html>
<html lang="en">
<head>
<meta charset="utf-8" />
<title>roslibjs simple example</title>
</head>
<body>
<h1>Simple roslib Example</h1>
<p>Run the following commands in the terminal then refresh this page. Check the JavaScript
console for the output.</p>
<ol>
<li><tt>roscore</tt></li>
<li><tt>rostopic pub /listener std_msgs/String "Hello, World"</tt></li>
<li><tt>rostopic echo /cmd_vel</tt></li>
<li><tt>rosrun rospy_tutorials add_two_ints_server</tt></li>
<li><tt>roslaunch rosbridge_server rosbridge_websocket.launch</tt></li>
</ol>
<script type="module">
import {
Ros,
Topic,
Message,
Service,
ServiceRequest,
Param,
} from '../build/roslib.js';
const ros = new Ros();
ros.on('error', function(error) {
console.log("Connection error: ", error);
});
ros.on('connection', function() {
console.log('Connection made!');
});
ros.on('close', function() {
console.log('Connection closed.');
});
ros.connect('ws://192.168.0.206:9090');
// Publishing a Topic
const cmdVel = new Topic({
ros : ros,
name : '/cmd_vel',
messageType : 'geometry_msgs/Twist'
});
const twist = new 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
const listener = new Topic({
ros : ros, name : '/listener', messageType : 'std_msgs/String'
});
// Then we add a callback to be called every time a message is published on this topic.
listener.subscribe(function(message) {
console.log('Received message on ' + listener.name + ': ' + message.data);
// listener.unsubscribe();
});
// Calling a service
const addTwoIntsClient = new Service({
ros : ros,
name : '/add_two_ints',
serviceType : 'rospy_tutorials/AddTwoInts'
});
const request = new ServiceRequest({
a : 1, b : 2
});
addTwoIntsClient.callService(request, function(result) {
console.log('Result for service call on ' + addTwoIntsClient.name + ': ' + result.sum);
});
// Advertising a Service
const setBoolServer = new Service({
ros : ros,
name : '/set_bool',
serviceType : 'std_srvs/SetBool'
});
setBoolServer.advertise(function(request, response) {
console.log('Received service request on ' + setBoolServer.name + ': ' + request.data);
response['success'] = true;
response['message'] = 'Set successfully';
return true;
});
// Get list of available params
ros.getParams(function(params) {
console.log('Params:');
console.log(params);
});
// Get list of available topics
ros.getTopics(function(topics) {
console.log('Topics:');
console.log(topics);
});
// First, we create a Param object with the name of the param.
const maxVelX = new Param({
ros : ros, name : 'max_vel_y'
});
//Then we set the value of the param, which is sent to the ROS Parameter Server.
maxVelX.set(0.8);
maxVelX.get(function(value) {
console.log('MAX VAL: ' + value);
});
// Getting a param value
// ---------------------
const favoriteColor = new Param({
ros : ros, name : 'favorite_color'
});
favoriteColor.set('red');
favoriteColor.get(function(value) {
console.log('My robot\'s favorite color is ' + value);
});
</script>
</body>
</html>