2 * @author Russell Toris - rctoris@wpi.edu
5 var KEYBOARDTELEOP = KEYBOARDTELEOP || {
10 * @author Russell Toris - rctoris@wpi.edu
14 * Manages connection to the server and all interactions with ROS.
16 * Emits the following events:
17 * * 'change' - emitted with a change in speed occurs
20 * @param options - possible keys include:
21 * * ros - the ROSLIB.Ros connection handle
22 * * topic (optional) - the Twist topic to publish to, like '/cmd_vel'
23 * * throttle (optional) - a constant throttle for the speed
25 KEYBOARDTELEOP.Teleop = function(options) {
27 options = options || {};
28 var ros = options.ros;
29 var topic = options.topic || '/cmd_vel';
31 var throttle = options.throttle || 1.0;
33 // used to externally throttle the speed (e.g., from a slider)
36 // linear x and y movement and angular z movement
41 var cmdVel = new ROSLIB.Topic({
44 messageType : 'geometry_msgs/Twist'
47 // sets up a key listener on the page used for keyboard teleoperation
48 var handleKey = function(keyCode, keyDown) {
49 // used to check for changes in speed
57 // throttle the speed by the slider and throttle constant
58 if (keyDown === true) {
59 speed = throttle * that.scale;
61 // check which key was pressed
91 // publish the command
93 var twist = new ROSLIB.Message({
105 cmdVel.publish(twist);
108 if (oldX !== x || oldY !== y || oldZ !== z) {
109 that.emit('change', twist);
115 var body = document.getElementsByTagName('body')[0];
116 body.addEventListener('keydown', function(e) {
117 handleKey(e.keyCode, true);
119 body.addEventListener('keyup', function(e) {
120 handleKey(e.keyCode, false);
123 KEYBOARDTELEOP.Teleop.prototype.__proto__ = EventEmitter2.prototype;