|
| 1 | +<!DOCTYPE html> |
| 2 | +<html> |
| 3 | +<head> |
| 4 | +<meta charset="utf-8" /> |
| 5 | +<script src="https://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script> |
| 6 | +<script src="../build/roslib.js"></script> |
| 7 | + |
| 8 | +<script> |
| 9 | + // Connecting to ROS |
| 10 | + // ----------------- |
| 11 | + var ros = new ROSLIB.Ros(); |
| 12 | + |
| 13 | + // If there is an error on the backend, an 'error' emit will be emitted. |
| 14 | + ros.on('error', function(error) { |
| 15 | + document.getElementById('connecting').style.display = 'none'; |
| 16 | + document.getElementById('connected').style.display = 'none'; |
| 17 | + document.getElementById('closed').style.display = 'none'; |
| 18 | + document.getElementById('error').style.display = 'inline'; |
| 19 | + console.log(error); |
| 20 | + }); |
| 21 | + |
| 22 | + // Find out exactly when we made a connection. |
| 23 | + ros.on('connection', function() { |
| 24 | + console.log('Connection made!'); |
| 25 | + document.getElementById('connecting').style.display = 'none'; |
| 26 | + document.getElementById('error').style.display = 'none'; |
| 27 | + document.getElementById('closed').style.display = 'none'; |
| 28 | + document.getElementById('connected').style.display = 'inline'; |
| 29 | + }); |
| 30 | + |
| 31 | + ros.on('close', function() { |
| 32 | + console.log('Connection closed.'); |
| 33 | + document.getElementById('connecting').style.display = 'none'; |
| 34 | + document.getElementById('connected').style.display = 'none'; |
| 35 | + document.getElementById('closed').style.display = 'inline'; |
| 36 | + }); |
| 37 | + |
| 38 | + // Create a connection to the rosbridge WebSocket server. |
| 39 | + ros.connect('ws://localhost:9090'); |
| 40 | + |
| 41 | + // Publishing a Topic |
| 42 | + // ------------------ |
| 43 | + |
| 44 | + // First, we create a Topic object with details of the topic's name and message type. |
| 45 | + var cmdVel = new ROSLIB.Topic({ |
| 46 | + ros : ros, |
| 47 | + name : '/cmd_vel', |
| 48 | + messageType : 'geometry_msgs/Twist' |
| 49 | + }); |
| 50 | + |
| 51 | + // Then we create the payload to be published. The object we pass in to ros.Message matches the |
| 52 | + // fields defined in the geometry_msgs/Twist.msg definition. |
| 53 | + var twist = new ROSLIB.Message({ |
| 54 | + linear : { |
| 55 | + x : 0.1, |
| 56 | + y : 0.2, |
| 57 | + z : 0.3 |
| 58 | + }, |
| 59 | + angular : { |
| 60 | + x : -0.1, |
| 61 | + y : -0.2, |
| 62 | + z : -0.3 |
| 63 | + } |
| 64 | + }); |
| 65 | + |
| 66 | + // And finally, publish. |
| 67 | + cmdVel.publish(twist); |
| 68 | + |
| 69 | + // Subscribing to a Topic |
| 70 | + // ---------------------- |
| 71 | + |
| 72 | + // Like when publishing a topic, we first create a Topic object with details of the topic's name |
| 73 | + // and message type. Note that we can call publish or subscribe on the same topic object. |
| 74 | + var listener = new ROSLIB.Topic({ |
| 75 | + ros : ros, |
| 76 | + name : '/listener', |
| 77 | + messageType : 'std_msgs/String' |
| 78 | + }); |
| 79 | + |
| 80 | + // Then we add a callback to be called every time a message is published on this topic. |
| 81 | + listener.subscribe(function(message) { |
| 82 | + console.log('Received message on ' + listener.name + ': ' + message.data); |
| 83 | + |
| 84 | + // If desired, we can unsubscribe from the topic as well. |
| 85 | + listener.unsubscribe(); |
| 86 | + }); |
| 87 | + |
| 88 | + // Calling a service |
| 89 | + // ----------------- |
| 90 | + |
| 91 | + // First, we create a Service client with details of the service's name and service type. |
| 92 | + var addTwoIntsClient = new ROSLIB.Service({ |
| 93 | + ros : ros, |
| 94 | + name : '/add_two_ints', |
| 95 | + serviceType : 'example_interfaces/AddTwoInts' |
| 96 | + }); |
| 97 | + |
| 98 | + // Then we create a Service Request. The object we pass in to ROSLIB.ServiceRequest matches the |
| 99 | + // fields defined in the rospy_tutorials AddTwoInts.srv file. |
| 100 | + var request = new ROSLIB.ServiceRequest({ |
| 101 | + a : 1, |
| 102 | + b : 2 |
| 103 | + }); |
| 104 | + |
| 105 | + // Finally, we call the /add_two_ints service and get back the results in the callback. The result |
| 106 | + // is a ROSLIB.ServiceResponse object. |
| 107 | + addTwoIntsClient.callService(request, function(result) { |
| 108 | + console.log('Result for service call on ' + addTwoIntsClient.name + ': ' + result.sum); |
| 109 | + }); |
| 110 | + |
| 111 | + // Advertising a Service |
| 112 | + // --------------------- |
| 113 | + |
| 114 | + // The Service object does double duty for both calling and advertising services |
| 115 | + var setBoolServer = new ROSLIB.Service({ |
| 116 | + ros : ros, |
| 117 | + name : '/set_bool', |
| 118 | + serviceType : 'std_srvs/SetBool' |
| 119 | + }); |
| 120 | + |
| 121 | + // Use the advertise() method to indicate that we want to provide this service |
| 122 | + setBoolServer.advertise(function(request, response) { |
| 123 | + console.log('Received service request on ' + setBoolServer.name + ': ' + request.data); |
| 124 | + response['success'] = true; |
| 125 | + response['message'] = 'Set successfully'; |
| 126 | + return true; |
| 127 | + }); |
| 128 | + |
| 129 | + // Getting a param value |
| 130 | + // --------------------- |
| 131 | + |
| 132 | + // In ROS 2, params are set in the format 'node_name:param_name' |
| 133 | + var favoriteColor = new ROSLIB.Param({ |
| 134 | + ros : ros, |
| 135 | + name : '/add_two_ints_server:use_sim_time' |
| 136 | + }); |
| 137 | + |
| 138 | + favoriteColor.get(function(value) { |
| 139 | + console.log('The value of use_sim_time before setting is ' + value); |
| 140 | + }); |
| 141 | + favoriteColor.set(true); |
| 142 | + favoriteColor.get(function(value) { |
| 143 | + console.log('The value of use_sim_time after setting is ' + value); |
| 144 | + }); |
| 145 | +</script> |
| 146 | +</head> |
| 147 | + |
| 148 | +<body> |
| 149 | + <h1>Simple roslib Example</h1> |
| 150 | + <p>Run the following commands in the terminal then refresh this page. Check the JavaScript |
| 151 | + console for the output.</p> |
| 152 | + <ol> |
| 153 | + <li><tt>ros2 topic pub /listener std_msgs/msg/String "{ data: 'hello world' }" </tt></li> |
| 154 | + <li><tt>ros2 topic echo /cmd_vel</tt></li> |
| 155 | + <li><tt>ros2 run demo_nodes_py add_two_ints_server</tt></li> |
| 156 | + <li><tt>ros2 launch rosbridge_server rosbridge_websocket_launch.xml</tt></li> |
| 157 | + </ol> |
| 158 | + <div id="statusIndicator"> |
| 159 | + <p id="connecting"> |
| 160 | + Connecting to rosbridge... |
| 161 | + </p> |
| 162 | + <p id="connected" style="color:#00D600; display:none"> |
| 163 | + Connected |
| 164 | + </p> |
| 165 | + <p id="error" style="color:#FF0000; display:none"> |
| 166 | + Error in the backend! |
| 167 | + </p> |
| 168 | + <p id="closed" style="display:none"> |
| 169 | + Connection closed. |
| 170 | + </p> |
| 171 | + </div> |
| 172 | +</body> |
| 173 | +</html> |
0 commit comments