From 1f9f8613a857966fe3ab38b78e1e22f945484e60 Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Fri, 15 Mar 2013 14:16:26 -0700 Subject: [PATCH 1/3] actionlib module converted to new ROSLIB standard --- build/roslib.js | 279 ++++++----- build/roslib.min.js | 2 +- doc/files.html | 18 +- doc/index.html | 18 +- doc/symbols/ROSLIB.ActionClient.html | 395 +++++++++++++++ doc/symbols/ROSLIB.Goal.html | 435 +++++++++++++++++ doc/symbols/ROSLIB.Message.html | 6 +- doc/symbols/ROSLIB.Param.html | 6 +- doc/symbols/ROSLIB.Ros.html | 8 +- doc/symbols/ROSLIB.Service.html | 6 +- doc/symbols/ROSLIB.ServiceRequest.html | 6 +- doc/symbols/ROSLIB.ServiceResponse.html | 6 +- doc/symbols/ROSLIB.Topic.html | 10 +- doc/symbols/_global_.html | 6 +- ...oslibjs_src_actionlib_ActionClient.js.html | 258 +++++----- ...vy_src_roslibjs_src_actionlib_Goal.js.html | 91 ++++ ...groovy_src_roslibjs_src_core_Param.js.html | 3 +- ...S_groovy_src_roslibjs_src_core_Ros.js.html | 450 +++++++++--------- ...oovy_src_roslibjs_src_core_Service.js.html | 3 +- ...groovy_src_roslibjs_src_core_Topic.js.html | 268 ++++++----- examples/fibonacci.html | 58 +++ src/actionlib/ActionClient.js | 204 ++++---- src/actionlib/Goal.js | 83 ++++ utils/build.xml | 2 +- 24 files changed, 1865 insertions(+), 756 deletions(-) create mode 100644 doc/symbols/ROSLIB.ActionClient.html create mode 100644 doc/symbols/ROSLIB.Goal.html create mode 100644 doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html create mode 100644 examples/fibonacci.html create mode 100644 src/actionlib/Goal.js diff --git a/build/roslib.js b/build/roslib.js index 4d2bbb08e..dc0eb7cc6 100644 --- a/build/roslib.js +++ b/build/roslib.js @@ -5,82 +5,100 @@ var ROSLIB = ROSLIB || { REVISION : '1' }; -(function (root, factory) { - if(typeof define === 'function' && define.amd) { - define(['eventemitter2'],factory); - } - else { - root.ActionClient = factory(root.EventEmitter2); - } -}(this, function(EventEmitter2) { +/** + * @author Russell Toris - rctoris@wpi.edu + */ -var ActionClient = function(options) { - var actionClient = this; +/** + * An actionlib action client. + * + * Emits the following events: + * * 'timeout' - if a timeout occurred while sending a goal + * * 'status' - the status messages received from the action server + * * 'feedback' - the feedback messages received from the action server + * * 'result' - the result returned from the action server + * + * @constructor + * @param options - object with following keys: + * * ros - the ROSLIB.Ros connection handle + * * serverName - the action server name, like /fibonacci + * * actionName - the action message name, like 'actionlib_tutorials/FibonacciAction' + * * timeout - the timeout length when connecting to the action server + */ +ROSLIB.ActionClient = function(options) { + var that = this; options = options || {}; - actionClient.ros = options.ros; - actionClient.serverName = options.serverName; - actionClient.actionName = options.actionName; - actionClient.timeout = options.timeout; - actionClient.goals = {}; - - actionClient.goalTopic = new actionClient.ros.Topic({ - name : actionClient.serverName + '/goal' - , messageType : actionClient.actionName + 'Goal' - }); - actionClient.goalTopic.advertise(); - - actionClient.cancelTopic = new actionClient.ros.Topic({ - name : actionClient.serverName + '/cancel' - , messageType : 'actionlib_msgs/GoalID' - }); - actionClient.cancelTopic.advertise(); + this.ros = options.ros; + this.serverName = options.serverName; + this.actionName = options.actionName; + this.timeout = options.timeout; + this.goals = {}; + // flag to check if a status has been received var receivedStatus = false; - var statusListener = new actionClient.ros.Topic({ - name : actionClient.serverName + '/status' - , messageType : 'actionlib_msgs/GoalStatusArray' + + // create the topics associated with actionlib + var feedbackListener = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/feedback', + messageType : this.actionName + 'Feedback' }); - statusListener.subscribe(function (statusMessage) { - receivedStatus = true; + var statusListener = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/status', + messageType : 'actionlib_msgs/GoalStatusArray' + }); + var resultListener = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/result', + messageType : this.actionName + 'Result' + }); + this.goalTopic = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/goal', + messageType : this.actionName + 'Goal' + }); + this.cancelTopic = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/cancel', + messageType : 'actionlib_msgs/GoalID' + }); + + /** + * Cancel all goals associated with this ActionClient. + */ + this.cancel = function() { + var cancelMessage = new ROSLIB.Message({}); + this.cancelTopic.publish(cancelMessage); + }; + + // advertise the goal and cancel topics + this.goalTopic.advertise(); + this.cancelTopic.advertise(); + // subscribe to the status topic + statusListener.subscribe(function(statusMessage) { + receivedStatus = true; statusMessage.status_list.forEach(function(status) { - var goal = actionClient.goals[status.goal_id.id]; + var goal = that.goals[status.goal_id.id]; if (goal) { goal.emit('status', status); } }); }); - // If timeout specified, emit a 'timeout' event if the ActionServer does not - // respond before the timeout. - if (actionClient.timeout) { - setTimeout(function() { - if (!receivedStatus) { - actionClient.emit('timeout'); - } - }, actionClient.timeout); - } - - // Subscribe to the feedback, and result topics - var feedbackListener = new actionClient.ros.Topic({ - name : actionClient.serverName + '/feedback' - , messageType : actionClient.actionName + 'Feedback' - }); - feedbackListener.subscribe(function (feedbackMessage) { - var goal = actionClient.goals[feedbackMessage.status.goal_id.id]; - + // subscribe the the feedback topic + feedbackListener.subscribe(function(feedbackMessage) { + var goal = that.goals[feedbackMessage.status.goal_id.id]; if (goal) { goal.emit('status', feedbackMessage.status); goal.emit('feedback', feedbackMessage.feedback); } }); - var resultListener = new actionClient.ros.Topic({ - name : actionClient.serverName + '/result' - , messageType : actionClient.actionName + 'Result' - }); - resultListener.subscribe(function (resultMessage) { - var goal = actionClient.goals[resultMessage.status.goal_id.id]; + // subscribe to the result topic + resultListener.subscribe(function(resultMessage) { + var goal = that.goals[resultMessage.status.goal_id.id]; if (goal) { goal.emit('status', resultMessage.status); @@ -88,72 +106,99 @@ var ActionClient = function(options) { } }); - actionClient.cancel = function() { - var cancelMessage = new actionClient.ros.Message({}); - actionClient.cancelTopic.publish(cancelMessage); - }; + // If timeout specified, emit a 'timeout' event if the action server does not respond + if (this.timeout) { + setTimeout(function() { + if (!receivedStatus) { + that.emit('timeout'); + } + }, this.timeout); + } +}; +ROSLIB.ActionClient.prototype.__proto__ = EventEmitter2.prototype; +/** + * @author Russell Toris - rctoris@wpi.edu + */ + +/** + * An actionlib goal that is associated with an action server. + * + * Emits the following events: + * * 'timeout' - if a timeout occurred while sending a goal + * + * @constructor + * @param object with following keys: + * * actionClient - the ROSLIB.ActionClient to use with this goal + * * goalMessage - The JSON object containing the goal for the action server + */ + +ROSLIB.Goal = function(options) { + var that = this; + this.actionClient = options.actionClient; + this.goalMessage = options.goalMessage; + this.isFinished = false; - actionClient.Goal = function(goalMsg) { - var goal = this; - - goal.isFinished = false; - goal.status; - goal.result; - goal.feedback; - - var date = new Date(); - goal.goalId = 'goal_' + Math.random() + "_" + date.getTime(); - goal.goalMessage = new actionClient.ros.Message({ - goal_id : { - stamp: { - secs : 0 - , nsecs : 0 + // used to create random IDs + var date = new Date(); + + /** + * Send the goal to the action server. + * + * @param timeout (optional) - a timeout length for the goal's result + */ + this.send = function(timeout) { + that.actionClient.goalTopic.publish(that.goalMessage); + if (timeout) { + setTimeout(function() { + if (!that.isFinished) { + that.emit('timeout'); } - , id: goal.goalId - } - , goal: goalMsg - }); + }, timeout); + } + }; - goal.on('status', function(status) { - goal.status = status; + /** + * Cancel the current this. + */ + this.cancel = function() { + var cancelMessage = new ROSLIB.Message({ + id : that.goalID }); + that.actionClient.cancelTopic.publish(cancelMessage); + }; - goal.on('result', function(result) { - goal.isFinished = true; - goal.result = result; - }); + // create a random ID + this.goalID = 'goal_' + Math.random() + "_" + date.getTime(); + // fill in the goal message + this.goalMessage = new ROSLIB.Message({ + goal_id : { + stamp : { + secs : 0, + nsecs : 0 + }, + id : this.goalID + }, + goal : this.goalMessage + }); - goal.on('feedback', function(feedback) { - goal.feedback = feedback; - }); + this.on('status', function(status) { + this.status = status; + }); - actionClient.goals[goal.goalId] = this; + this.on('result', function(result) { + this.isFinished = true; + this.result = result; + }); - goal.send = function(timeout) { - actionClient.goalTopic.publish(goal.goalMessage); - if (timeout) { - setTimeout(function() { - if (!goal.isFinished) { - goal.emit('timeout'); - } - }, timeout); - } - }; + this.on('feedback', function(feedback) { + this.feedback = feedback; + }); - goal.cancel = function() { - var cancelMessage = new actionClient.ros.Message({ - id: goal.goalId - }); - actionClient.cancelTopic.publish(cancelMessage); - }; - }; - actionClient.Goal.prototype.__proto__ = EventEmitter2.prototype; + // add the goal + this.actionClient.goals[this.goalID] = this; }; -ActionClient.prototype.__proto__ = EventEmitter2.prototype; -return ActionClient; -} -)); +ROSLIB.Goal.prototype.__proto__ = EventEmitter2.prototype; /** * @author Brandon Alexander - balexander@willowgarage.com */ @@ -231,7 +276,6 @@ ROSLIB.Param = function(options) { }); }; }; -ROSLIB.Param.prototype.__proto__ = EventEmitter2.prototype; /** * @author Brandon Alexander - balexander@willowgarage.com */ @@ -243,6 +287,8 @@ ROSLIB.Param.prototype.__proto__ = EventEmitter2.prototype; * * 'error' - there was an error with ROS * * 'connection' - connected to the WebSocket server * * 'close' - disconnected to the WebSocket server + * * - a message came from rosbridge with the given topic name + * * - a service response came from rosbridge with the given ID * * @constructor * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. @@ -518,7 +564,6 @@ ROSLIB.Service = function(options) { ros.callOnConnection(call); }; }; -ROSLIB.Service.prototype.__proto__ = EventEmitter2.prototype; /** * @author Brandon Alexander - balexander@willowgarage.com */ @@ -561,7 +606,11 @@ ROSLIB.ServiceResponse = function(values) { /** * Publish and/or subscribe to a topic in ROS. - * + * + * Emits the following events: + * * 'warning' - if there are any warning during the Topic creation + * * 'message' - the message data from rosbridge + * * @constructor * @param options - object with following keys: * * ros - the ROSLIB.Ros connection handle diff --git a/build/roslib.min.js b/build/roslib.min.js index 4ead513e4..d3fc54001 100644 --- a/build/roslib.min.js +++ b/build/roslib.min.js @@ -1 +1 @@ -var ROSLIB=ROSLIB||{REVISION:"1"};(function(a,b){if(typeof define==="function"&&define.amd){define(["eventemitter2"],b)}else{a.ActionClient=b(a.EventEmitter2)}}(this,function(a){var b=function(d){var f=this;d=d||{};f.ros=d.ros;f.serverName=d.serverName;f.actionName=d.actionName;f.timeout=d.timeout;f.goals={};f.goalTopic=new f.ros.Topic({name:f.serverName+"/goal",messageType:f.actionName+"Goal"});f.goalTopic.advertise();f.cancelTopic=new f.ros.Topic({name:f.serverName+"/cancel",messageType:"actionlib_msgs/GoalID"});f.cancelTopic.advertise();var c=false;var g=new f.ros.Topic({name:f.serverName+"/status",messageType:"actionlib_msgs/GoalStatusArray"});g.subscribe(function(i){c=true;i.status_list.forEach(function(j){var k=f.goals[j.goal_id.id];if(k){k.emit("status",j)}})});if(f.timeout){setTimeout(function(){if(!c){f.emit("timeout")}},f.timeout)}var e=new f.ros.Topic({name:f.serverName+"/feedback",messageType:f.actionName+"Feedback"});e.subscribe(function(j){var i=f.goals[j.status.goal_id.id];if(i){i.emit("status",j.status);i.emit("feedback",j.feedback)}});var h=new f.ros.Topic({name:f.serverName+"/result",messageType:f.actionName+"Result"});h.subscribe(function(j){var i=f.goals[j.status.goal_id.id];if(i){i.emit("status",j.status);i.emit("result",j.result)}});f.cancel=function(){var i=new f.ros.Message({});f.cancelTopic.publish(i)};f.Goal=function(k){var j=this;j.isFinished=false;j.status;j.result;j.feedback;var i=new Date();j.goalId="goal_"+Math.random()+"_"+i.getTime();j.goalMessage=new f.ros.Message({goal_id:{stamp:{secs:0,nsecs:0},id:j.goalId},goal:k});j.on("status",function(l){j.status=l});j.on("result",function(l){j.isFinished=true;j.result=l});j.on("feedback",function(l){j.feedback=l});f.goals[j.goalId]=this;j.send=function(l){f.goalTopic.publish(j.goalMessage);if(l){setTimeout(function(){if(!j.isFinished){j.emit("timeout")}},l)}};j.cancel=function(){var l=new f.ros.Message({id:j.goalId});f.cancelTopic.publish(l)}};f.Goal.prototype.__proto__=a.prototype};b.prototype.__proto__=a.prototype;return b}));ROSLIB.Message=function(a){var b=this;if(a){Object.keys(a).forEach(function(c){b[c]=a[c]})}};ROSLIB.Param=function(a){var b=this;a=a||{};b.name=a.name;b.get=function(e){var d=new ROSLIB.Service({name:"/rosapi/get_param",serviceType:"rosapi/GetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify("")});d.callService(c,function(f){var g=JSON.parse(f.value);e(g)})};b.set=function(e){var d=new ROSLIB.Service({name:"/rosapi/set_param",serviceType:"rosapi/SetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify(e)});d.callService(c,function(){})}};ROSLIB.Param.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Ros=function(d){var c=this;c.socket=null;function b(h){c.emit("connection",h)}function a(h){c.emit("close",h)}function e(h){c.emit("error",h)}function g(h,j){var i=new Image();i.onload=function(){var k=document.createElement("canvas");var m=k.getContext("2d");k.width=i.width;k.height=i.height;m.drawImage(i,0,0);var p=m.getImageData(0,0,i.width,i.height).data;var n="";for(var l=0;l=0){j.cbs.splice(h,1);if(j.cbs.length==0){delete this.frame_infos[i]}this.needUpdate=true}}};var f=d.Pose=function(h,i){this.position=new a;this.orientation=new e;if(h!==undefined){this.position.copy(h)}if(i!==undefined){this.orientation.copy(i)}};f.prototype={constructor:f,copy:function(h){this.position.copy(h.position);this.orientation.copy(h.orientation)}};var c=d.Transform=function(i,h){this.translation=new a;this.rotation=new e;if(i!==undefined){this.translation.copy(i)}if(h!==undefined){this.rotation.copy(h)}};c.prototype={constructor:c,apply:function(h){this.rotation.multiplyVec3(h.position);h.position.add(h.position,this.translation);h.orientation.multiply(this.rotation,h.orientation);return h},applyInverse:function(i){var h=this.rotation.clone().inverse();h.multiplyVec3(i.position);i.position.sub(i.position,this.translation);i.orientation.multiply(h,i.orientation);return i},copy:function(h){this.translation.copy(h.translation);this.rotation.copy(h.rotation)}};var e=d.Quaternion=function(h,k,j,i){this.x=h||0;this.y=k||0;this.z=j||0;this.w=(i!==undefined)?i:1};e.prototype={constructor:e,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;this.w=h.w;return this},inverse:function(){this.conjugate().normalize();return this},conjugate:function(){this.x*=-1;this.y*=-1;this.z*=-1;return this},normalize:function(){var h=Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w);if(h===0){this.x=0;this.y=0;this.z=0;this.w=1}else{h=1/h;this.x=this.x*h;this.y=this.y*h;this.z=this.z*h;this.w=this.w*h}return this},multiply:function(q,p){var n=q.x,m=q.y,l=q.z,o=q.w,j=p.x,i=p.y,h=p.z,k=p.w;this.x=n*k+m*h-l*i+o*j;this.y=-n*h+m*k+l*j+o*i;this.z=n*i-m*j+l*k+o*h;this.w=-n*j-m*i-l*h+o*k;return this},multiplyVec3:function(j,t){if(!t){t=j}var s=j.x,r=j.y,q=j.z,o=this.x,n=this.y,m=this.z,p=this.w;var k=p*s+n*q-m*r,i=p*r+m*s-o*q,h=p*q+o*r-n*s,l=-o*s-n*r-m*q;t.x=k*p+l*-o+i*-m-h*-n;t.y=i*p+l*-n+h*-o-k*-m;t.z=h*p+l*-m+k*-n-i*-o;return t},clone:function(){return new e(this.x,this.y,this.z,this.w)}};var a=d.Vector3=function(h,j,i){this.x=h||0;this.y=j||0;this.z=i||0};a.prototype={constructor:a,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;return this},add:function(i,h){this.x=i.x+h.x;this.y=i.y+h.y;this.z=i.z+h.z;return this},sub:function(i,h){this.x=i.x-h.x;this.y=i.y-h.y;this.z=i.z-h.z;return this},clone:function(){return new a(this.x,this.y,this.z)}};return d})); \ No newline at end of file +var ROSLIB=ROSLIB||{REVISION:"1"};ROSLIB.ActionClient=function(b){var c=this;b=b||{};this.ros=b.ros;this.serverName=b.serverName;this.actionName=b.actionName;this.timeout=b.timeout;this.goals={};var a=false;var d=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/feedback",messageType:this.actionName+"Feedback"});var e=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/status",messageType:"actionlib_msgs/GoalStatusArray"});var f=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/result",messageType:this.actionName+"Result"});this.goalTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/goal",messageType:this.actionName+"Goal"});this.cancelTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/cancel",messageType:"actionlib_msgs/GoalID"});this.cancel=function(){var g=new ROSLIB.Message({});this.cancelTopic.publish(g)};this.goalTopic.advertise();this.cancelTopic.advertise();e.subscribe(function(g){a=true;g.status_list.forEach(function(h){var i=c.goals[h.goal_id.id];if(i){i.emit("status",h)}})});d.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("feedback",h.feedback)}});f.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("result",h.result)}});if(this.timeout){setTimeout(function(){if(!a){c.emit("timeout")}},this.timeout)}};ROSLIB.ActionClient.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Goal=function(b){var c=this;this.actionClient=b.actionClient;this.goalMessage=b.goalMessage;this.isFinished=false;var a=new Date();this.send=function(d){c.actionClient.goalTopic.publish(c.goalMessage);if(d){setTimeout(function(){if(!c.isFinished){c.emit("timeout")}},d)}};this.cancel=function(){var d=new ROSLIB.Message({id:c.goalID});c.actionClient.cancelTopic.publish(d)};this.goalID="goal_"+Math.random()+"_"+a.getTime();this.goalMessage=new ROSLIB.Message({goal_id:{stamp:{secs:0,nsecs:0},id:this.goalID},goal:this.goalMessage});this.on("status",function(d){this.status=d});this.on("result",function(d){this.isFinished=true;this.result=d});this.on("feedback",function(d){this.feedback=d});this.actionClient.goals[this.goalID]=this};ROSLIB.Goal.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Message=function(a){var b=this;if(a){Object.keys(a).forEach(function(c){b[c]=a[c]})}};ROSLIB.Param=function(a){var b=this;a=a||{};b.name=a.name;b.get=function(e){var d=new ROSLIB.Service({name:"/rosapi/get_param",serviceType:"rosapi/GetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify("")});d.callService(c,function(f){var g=JSON.parse(f.value);e(g)})};b.set=function(e){var d=new ROSLIB.Service({name:"/rosapi/set_param",serviceType:"rosapi/SetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify(e)});d.callService(c,function(){})}};ROSLIB.Ros=function(d){var c=this;c.socket=null;function b(h){c.emit("connection",h)}function a(h){c.emit("close",h)}function e(h){c.emit("error",h)}function g(h,j){var i=new Image();i.onload=function(){var k=document.createElement("canvas");var m=k.getContext("2d");k.width=i.width;k.height=i.height;m.drawImage(i,0,0);var p=m.getImageData(0,0,i.width,i.height).data;var n="";for(var l=0;l=0){j.cbs.splice(h,1);if(j.cbs.length==0){delete this.frame_infos[i]}this.needUpdate=true}}};var f=d.Pose=function(h,i){this.position=new a;this.orientation=new e;if(h!==undefined){this.position.copy(h)}if(i!==undefined){this.orientation.copy(i)}};f.prototype={constructor:f,copy:function(h){this.position.copy(h.position);this.orientation.copy(h.orientation)}};var c=d.Transform=function(i,h){this.translation=new a;this.rotation=new e;if(i!==undefined){this.translation.copy(i)}if(h!==undefined){this.rotation.copy(h)}};c.prototype={constructor:c,apply:function(h){this.rotation.multiplyVec3(h.position);h.position.add(h.position,this.translation);h.orientation.multiply(this.rotation,h.orientation);return h},applyInverse:function(i){var h=this.rotation.clone().inverse();h.multiplyVec3(i.position);i.position.sub(i.position,this.translation);i.orientation.multiply(h,i.orientation);return i},copy:function(h){this.translation.copy(h.translation);this.rotation.copy(h.rotation)}};var e=d.Quaternion=function(h,k,j,i){this.x=h||0;this.y=k||0;this.z=j||0;this.w=(i!==undefined)?i:1};e.prototype={constructor:e,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;this.w=h.w;return this},inverse:function(){this.conjugate().normalize();return this},conjugate:function(){this.x*=-1;this.y*=-1;this.z*=-1;return this},normalize:function(){var h=Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w);if(h===0){this.x=0;this.y=0;this.z=0;this.w=1}else{h=1/h;this.x=this.x*h;this.y=this.y*h;this.z=this.z*h;this.w=this.w*h}return this},multiply:function(q,p){var n=q.x,m=q.y,l=q.z,o=q.w,j=p.x,i=p.y,h=p.z,k=p.w;this.x=n*k+m*h-l*i+o*j;this.y=-n*h+m*k+l*j+o*i;this.z=n*i-m*j+l*k+o*h;this.w=-n*j-m*i-l*h+o*k;return this},multiplyVec3:function(j,t){if(!t){t=j}var s=j.x,r=j.y,q=j.z,o=this.x,n=this.y,m=this.z,p=this.w;var k=p*s+n*q-m*r,i=p*r+m*s-o*q,h=p*q+o*r-n*s,l=-o*s-n*r-m*q;t.x=k*p+l*-o+i*-m-h*-n;t.y=i*p+l*-n+h*-o-k*-m;t.z=h*p+l*-m+k*-n-i*-o;return t},clone:function(){return new e(this.x,this.y,this.z,this.w)}};var a=d.Vector3=function(h,j,i){this.x=h||0;this.y=j||0;this.z=i||0};a.prototype={constructor:a,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;return this},add:function(i,h){this.x=i.x+h.x;this.y=i.y+h.y;this.z=i.z+h.z;return this},sub:function(i,h){this.x=i.x-h.x;this.y=i.y-h.y;this.z=i.z-h.z;return this},clone:function(){return new a(this.x,this.y,this.z)}};return d})); \ No newline at end of file diff --git a/doc/files.html b/doc/files.html index b56439347..7a98933c3 100644 --- a/doc/files.html +++ b/doc/files.html @@ -186,6 +186,10 @@

Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -216,6 +220,18 @@

    /home/tor1pal/Documents/WPI/RAIL/ROS/groovy/src/roslibjs/src/actionlib/Goal.js

    + +
    + + + +

    @@ -332,7 +348,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) \ No newline at end of file diff --git a/doc/index.html b/doc/index.html index 8ac9d9203..9bae109e0 100644 --- a/doc/index.html +++ b/doc/index.html @@ -186,6 +186,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -214,6 +218,18 @@

    _global_


    + +
    + +
    +

    ROSLIB.Goal

    + +
    +
    +

    ROSLIB.Message

    @@ -260,7 +276,7 @@

    ROSLIB.Topic

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    \ No newline at end of file diff --git a/doc/symbols/ROSLIB.ActionClient.html b/doc/symbols/ROSLIB.ActionClient.html new file mode 100644 index 000000000..87aa2655c --- /dev/null +++ b/doc/symbols/ROSLIB.ActionClient.html @@ -0,0 +1,395 @@ + + + + + + + JsDoc Reference - ROSLIB.ActionClient + + + + + + + + + + + + + +
    + +

    + + Class ROSLIB.ActionClient +

    + + +

    + + + + + + +
    Defined in: ActionClient.js. + +

    + + + + + + + + + + + + + + + + + +
    Class Summary
    Constructor AttributesConstructor Name and Description
      +
    + ROSLIB.ActionClient(options) +
    +
    An actionlib action client.
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + +
    Method Summary
    Method AttributesMethod Name and Description
      +
    cancel() +
    +
    Cancel all goals associated with this ActionClient.
    +
    + + + + + + + + + +
    +
    + Class Detail +
    + +
    + ROSLIB.ActionClient(options) +
    + +
    + An actionlib action client. + +Emits the following events: + * 'timeout' - if a timeout occurred while sending a goal + * 'status' - the status messages received from the action server + * 'feedback' - the feedback messages received from the action server + * 'result' - the result returned from the action server + +
    + + + + + +
    +
    Parameters:
    + +
    + options + +
    +
    - object with following keys: + * ros - the ROSLIB.Ros connection handle + * serverName - the action server name, like /fibonacci + * actionName - the action message name, like 'actionlib_tutorials/FibonacciAction' + * timeout - the timeout length when connecting to the action server
    + +
    + + + + + + + + +
    + + + + + + + +
    + Method Detail +
    + + +
    + + + cancel() + +
    +
    + Cancel all goals associated with this ActionClient. + + +
    + + + + + + + + + + + + + + + + + + +
    +
    + + + +
    + + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT) +
    + + diff --git a/doc/symbols/ROSLIB.Goal.html b/doc/symbols/ROSLIB.Goal.html new file mode 100644 index 000000000..5dc057c3d --- /dev/null +++ b/doc/symbols/ROSLIB.Goal.html @@ -0,0 +1,435 @@ + + + + + + + JsDoc Reference - ROSLIB.Goal + + + + + + + + + + + + + +
    + +

    + + Class ROSLIB.Goal +

    + + +

    + + + + + + +
    Defined in: Goal.js. + +

    + + + + + + + + + + + + + + + + + +
    Class Summary
    Constructor AttributesConstructor Name and Description
      +
    + ROSLIB.Goal(object) +
    +
    An actionlib goal that is associated with an action server.
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    Method Summary
    Method AttributesMethod Name and Description
      +
    cancel() +
    +
    Cancel the current this.
    +
      +
    send(timeout) +
    +
    Send the goal to the action server.
    +
    + + + + + + + + + +
    +
    + Class Detail +
    + +
    + ROSLIB.Goal(object) +
    + +
    + An actionlib goal that is associated with an action server. + +Emits the following events: + * 'timeout' - if a timeout occurred while sending a goal + +
    + + + + + +
    +
    Parameters:
    + +
    + object + +
    +
    with following keys: + * actionClient - the ROSLIB.ActionClient to use with this goal + * goalMessage - The JSON object containing the goal for the action server
    + +
    + + + + + + + + +
    + + + + + + + +
    + Method Detail +
    + + +
    + + + cancel() + +
    +
    + Cancel the current this. + + +
    + + + + + + + + + + + +
    + + +
    + + + send(timeout) + +
    +
    + Send the goal to the action server. + + +
    + + + + +
    +
    Parameters:
    + +
    + timeout + +
    +
    (optional) - a timeout length for the goal's result
    + +
    + + + + + + + + + + + + + + + +
    +
    + + + +
    + + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT) +
    + + diff --git a/doc/symbols/ROSLIB.Message.html b/doc/symbols/ROSLIB.Message.html index 2d1ac9766..9fc1928ff 100644 --- a/doc/symbols/ROSLIB.Message.html +++ b/doc/symbols/ROSLIB.Message.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -318,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Param.html b/doc/symbols/ROSLIB.Param.html index de2dd745f..1c22ed657 100644 --- a/doc/symbols/ROSLIB.Param.html +++ b/doc/symbols/ROSLIB.Param.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -319,7 +323,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Ros.html b/doc/symbols/ROSLIB.Ros.html index be1e24551..35a07d2c0 100644 --- a/doc/symbols/ROSLIB.Ros.html +++ b/doc/symbols/ROSLIB.Ros.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -344,6 +348,8 @@

    * 'error' - there was an error with ROS * 'connection' - connected to the WebSocket server * 'close' - disconnected to the WebSocket server + * - a message came from rosbridge with the given topic name + * - a service response came from rosbridge with the given ID @@ -582,7 +588,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Service.html b/doc/symbols/ROSLIB.Service.html index 6181387bd..444965cb9 100644 --- a/doc/symbols/ROSLIB.Service.html +++ b/doc/symbols/ROSLIB.Service.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -318,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.ServiceRequest.html b/doc/symbols/ROSLIB.ServiceRequest.html index c9397efb5..95b6809f4 100644 --- a/doc/symbols/ROSLIB.ServiceRequest.html +++ b/doc/symbols/ROSLIB.ServiceRequest.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -318,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.ServiceResponse.html b/doc/symbols/ROSLIB.ServiceResponse.html index 27e1cf123..c69d8b412 100644 --- a/doc/symbols/ROSLIB.ServiceResponse.html +++ b/doc/symbols/ROSLIB.ServiceResponse.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -318,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Topic.html b/doc/symbols/ROSLIB.Topic.html index ed1958b76..ce7941d06 100644 --- a/doc/symbols/ROSLIB.Topic.html +++ b/doc/symbols/ROSLIB.Topic.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -274,6 +278,10 @@

    Publish and/or subscribe to a topic in ROS. + +Emits the following events: + * 'warning' - if there are any warning during the Topic creation + * 'message' - the message data from rosbridge
    @@ -323,7 +331,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT)
    diff --git a/doc/symbols/_global_.html b/doc/symbols/_global_.html index c45a9bec1..1ef15c8a6 100644 --- a/doc/symbols/_global_.html +++ b/doc/symbols/_global_.html @@ -191,6 +191,10 @@

    Classes

  • _global_
  • +
  • ROSLIB.ActionClient
  • + +
  • ROSLIB.Goal
  • +
  • ROSLIB.Message
  • ROSLIB.Param
  • @@ -315,7 +319,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 11:56:50 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT)
    diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html index 96f1d8632..8ce886c40 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html @@ -5,153 +5,115 @@ .STRN {color: #393;} .REGX {color: #339;} .line {border-right: 1px dotted #666; color: #666; font-style: normal;} -
      1 (function (root, factory) {
    -  2     if(typeof define === 'function' && define.amd) {
    -  3         define(['eventemitter2'],factory);
    -  4     }
    -  5     else {
    -  6         root.ActionClient = factory(root.EventEmitter2);
    -  7     }
    -  8 }(this, function(EventEmitter2) {
    -  9 
    - 10 var ActionClient = function(options) {
    - 11   var actionClient = this;
    - 12   options = options || {};
    - 13   actionClient.ros         = options.ros;
    - 14   actionClient.serverName  = options.serverName;
    - 15   actionClient.actionName  = options.actionName;
    - 16   actionClient.timeout     = options.timeout;
    - 17   actionClient.goals       = {};
    - 18 
    - 19   actionClient.goalTopic = new actionClient.ros.Topic({
    - 20     name        : actionClient.serverName + '/goal'
    - 21   , messageType : actionClient.actionName + 'Goal'
    - 22   });
    - 23   actionClient.goalTopic.advertise();
    - 24 
    - 25   actionClient.cancelTopic = new actionClient.ros.Topic({
    - 26     name        : actionClient.serverName + '/cancel'
    - 27   , messageType : 'actionlib_msgs/GoalID'
    - 28   });
    - 29   actionClient.cancelTopic.advertise();
    - 30 
    +	
      1 /**
    +  2  * @author Russell Toris - rctoris@wpi.edu
    +  3  */
    +  4 
    +  5 /**
    +  6  * An actionlib action client.
    +  7  *
    +  8  * Emits the following events:
    +  9  *  * 'timeout' - if a timeout occurred while sending a goal
    + 10  *  * 'status' - the status messages received from the action server
    + 11  *  * 'feedback' -  the feedback messages received from the action server
    + 12  *  * 'result' - the result returned from the action server
    + 13  *
    + 14  *  @constructor
    + 15  *  @param options - object with following keys:
    + 16  *   * ros - the ROSLIB.Ros connection handle
    + 17  *   * serverName - the action server name, like /fibonacci
    + 18  *   * actionName - the action message name, like 'actionlib_tutorials/FibonacciAction'
    + 19  *   * timeout - the timeout length when connecting to the action server
    + 20  */
    + 21 ROSLIB.ActionClient = function(options) {
    + 22   var that = this;
    + 23   options = options || {};
    + 24   this.ros = options.ros;
    + 25   this.serverName = options.serverName;
    + 26   this.actionName = options.actionName;
    + 27   this.timeout = options.timeout;
    + 28   this.goals = {};
    + 29 
    + 30   // flag to check if a status has been received
      31   var receivedStatus = false;
    - 32   var statusListener = new actionClient.ros.Topic({
    - 33     name        : actionClient.serverName + '/status'
    - 34   , messageType : 'actionlib_msgs/GoalStatusArray'
    - 35   });
    - 36   statusListener.subscribe(function (statusMessage) {
    - 37     receivedStatus = true;
    - 38 
    - 39     statusMessage.status_list.forEach(function(status) {
    - 40       var goal = actionClient.goals[status.goal_id.id];
    - 41       if (goal) {
    - 42         goal.emit('status', status);
    - 43       }
    - 44     });
    - 45   });
    - 46 
    - 47   // If timeout specified, emit a 'timeout' event if the ActionServer does not
    - 48   // respond before the timeout.
    - 49   if (actionClient.timeout) {
    - 50     setTimeout(function() {
    - 51       if (!receivedStatus) {
    - 52         actionClient.emit('timeout');
    - 53       }
    - 54     }, actionClient.timeout);
    - 55   }
    - 56 
    - 57   // Subscribe to the feedback, and result topics
    - 58   var feedbackListener = new actionClient.ros.Topic({
    - 59     name        : actionClient.serverName + '/feedback'
    - 60   , messageType : actionClient.actionName + 'Feedback'
    - 61   });
    - 62   feedbackListener.subscribe(function (feedbackMessage) {
    - 63     var goal = actionClient.goals[feedbackMessage.status.goal_id.id];
    - 64 
    - 65     if (goal) {
    - 66       goal.emit('status', feedbackMessage.status);
    - 67       goal.emit('feedback', feedbackMessage.feedback);
    - 68     }
    - 69   });
    - 70 
    - 71   var resultListener = new actionClient.ros.Topic({
    - 72     name        : actionClient.serverName + '/result'
    - 73   , messageType : actionClient.actionName + 'Result'
    - 74   });
    - 75   resultListener.subscribe(function (resultMessage) {
    - 76     var goal = actionClient.goals[resultMessage.status.goal_id.id];
    - 77 
    - 78     if (goal) {
    - 79       goal.emit('status', resultMessage.status);
    - 80       goal.emit('result', resultMessage.result);
    - 81     }
    - 82   });
    - 83 
    - 84   actionClient.cancel = function() {
    - 85     var cancelMessage = new actionClient.ros.Message({});
    - 86     actionClient.cancelTopic.publish(cancelMessage);
    - 87   };
    - 88 
    - 89   actionClient.Goal = function(goalMsg) {
    - 90     var goal = this;
    + 32 
    + 33   // create the topics associated with actionlib
    + 34   var feedbackListener = new ROSLIB.Topic({
    + 35     ros : this.ros,
    + 36     name : this.serverName + '/feedback',
    + 37     messageType : this.actionName + 'Feedback'
    + 38   });
    + 39   var statusListener = new ROSLIB.Topic({
    + 40     ros : this.ros,
    + 41     name : this.serverName + '/status',
    + 42     messageType : 'actionlib_msgs/GoalStatusArray'
    + 43   });
    + 44   var resultListener = new ROSLIB.Topic({
    + 45     ros : this.ros,
    + 46     name : this.serverName + '/result',
    + 47     messageType : this.actionName + 'Result'
    + 48   });
    + 49   this.goalTopic = new ROSLIB.Topic({
    + 50     ros : this.ros,
    + 51     name : this.serverName + '/goal',
    + 52     messageType : this.actionName + 'Goal'
    + 53   });
    + 54   this.cancelTopic = new ROSLIB.Topic({
    + 55     ros : this.ros,
    + 56     name : this.serverName + '/cancel',
    + 57     messageType : 'actionlib_msgs/GoalID'
    + 58   });
    + 59 
    + 60   /**
    + 61    * Cancel all goals associated with this ActionClient.
    + 62    */
    + 63   this.cancel = function() {
    + 64     var cancelMessage = new ROSLIB.Message({});
    + 65     this.cancelTopic.publish(cancelMessage);
    + 66   };
    + 67 
    + 68   // advertise the goal and cancel topics
    + 69   this.goalTopic.advertise();
    + 70   this.cancelTopic.advertise();
    + 71 
    + 72   // subscribe to the status topic
    + 73   statusListener.subscribe(function(statusMessage) {
    + 74     receivedStatus = true;
    + 75     statusMessage.status_list.forEach(function(status) {
    + 76       var goal = that.goals[status.goal_id.id];
    + 77       if (goal) {
    + 78         goal.emit('status', status);
    + 79       }
    + 80     });
    + 81   });
    + 82 
    + 83   // subscribe the the feedback topic
    + 84   feedbackListener.subscribe(function(feedbackMessage) {
    + 85     var goal = that.goals[feedbackMessage.status.goal_id.id];
    + 86     if (goal) {
    + 87       goal.emit('status', feedbackMessage.status);
    + 88       goal.emit('feedback', feedbackMessage.feedback);
    + 89     }
    + 90   });
      91 
    - 92     goal.isFinished = false;
    - 93     goal.status;
    - 94     goal.result;
    - 95     goal.feedback;
    - 96 
    - 97     var date = new Date();
    - 98     goal.goalId = 'goal_' + Math.random() + "_" + date.getTime();
    - 99     goal.goalMessage = new actionClient.ros.Message({
    -100       goal_id : {
    -101         stamp: {
    -102           secs  : 0
    -103         , nsecs : 0
    -104         }
    -105       , id: goal.goalId
    -106       }
    -107     , goal: goalMsg
    -108     });
    -109 
    -110     goal.on('status', function(status) {
    -111       goal.status = status;
    -112     });
    -113 
    -114     goal.on('result', function(result) {
    -115       goal.isFinished = true;
    -116       goal.result = result;
    -117     });
    -118 
    -119     goal.on('feedback', function(feedback) {
    -120       goal.feedback = feedback;
    -121     });
    -122 
    -123     actionClient.goals[goal.goalId] = this;
    -124 
    -125     goal.send = function(timeout) {
    -126       actionClient.goalTopic.publish(goal.goalMessage);
    -127       if (timeout) {
    -128          setTimeout(function() {
    -129            if (!goal.isFinished) {
    -130              goal.emit('timeout');
    -131            }
    -132          }, timeout);
    -133       }
    -134     };
    -135 
    -136     goal.cancel = function() {
    -137       var cancelMessage = new actionClient.ros.Message({
    -138         id: goal.goalId
    -139       });
    -140       actionClient.cancelTopic.publish(cancelMessage);
    -141     };
    -142   };
    -143   actionClient.Goal.prototype.__proto__ = EventEmitter2.prototype;
    -144 
    -145 };
    -146 ActionClient.prototype.__proto__ = EventEmitter2.prototype;
    -147 return ActionClient;
    -148 }
    -149 ));
    -150 
    \ No newline at end of file + 92
    // subscribe to the result topic + 93 resultListener.subscribe(function(resultMessage) { + 94 var goal = that.goals[resultMessage.status.goal_id.id]; + 95 + 96 if (goal) { + 97 goal.emit('status', resultMessage.status); + 98 goal.emit('result', resultMessage.result); + 99 } +100 }); +101 +102 // If timeout specified, emit a 'timeout' event if the action server does not respond +103 if (this.timeout) { +104 setTimeout(function() { +105 if (!receivedStatus) { +106 that.emit('timeout'); +107 } +108 }, this.timeout); +109 } +110 }; +111 ROSLIB.ActionClient.prototype.__proto__ = EventEmitter2.prototype; +112
    \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html new file mode 100644 index 000000000..529d07cb9 --- /dev/null +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html @@ -0,0 +1,91 @@ +
      1 /**
    +  2  * @author Russell Toris - rctoris@wpi.edu
    +  3  */
    +  4 
    +  5 /**
    +  6  * An actionlib goal that is associated with an action server.
    +  7  *
    +  8  * Emits the following events:
    +  9  *  * 'timeout' - if a timeout occurred while sending a goal 
    + 10  *
    + 11  *  @constructor
    + 12  *  @param object with following keys:
    + 13  *   * actionClient - the ROSLIB.ActionClient to use with this goal
    + 14  *   * goalMessage - The JSON object containing the goal for the action server
    + 15  */
    + 16 
    + 17 ROSLIB.Goal = function(options) {
    + 18   var that = this;
    + 19   this.actionClient = options.actionClient;
    + 20   this.goalMessage = options.goalMessage;
    + 21   this.isFinished = false;
    + 22 
    + 23   // used to create random IDs
    + 24   var date = new Date();
    + 25 
    + 26   /**
    + 27    * Send the goal to the action server.
    + 28    * 
    + 29    * @param timeout (optional) - a timeout length for the goal's result
    + 30    */
    + 31   this.send = function(timeout) {
    + 32     that.actionClient.goalTopic.publish(that.goalMessage);
    + 33     if (timeout) {
    + 34       setTimeout(function() {
    + 35         if (!that.isFinished) {
    + 36           that.emit('timeout');
    + 37         }
    + 38       }, timeout);
    + 39     }
    + 40   };
    + 41 
    + 42   /**
    + 43    * Cancel the current this.
    + 44    */
    + 45   this.cancel = function() {
    + 46     var cancelMessage = new ROSLIB.Message({
    + 47       id : that.goalID
    + 48     });
    + 49     that.actionClient.cancelTopic.publish(cancelMessage);
    + 50   };
    + 51 
    + 52   // create a random ID
    + 53   this.goalID = 'goal_' + Math.random() + "_" + date.getTime();
    + 54   // fill in the goal message
    + 55   this.goalMessage = new ROSLIB.Message({
    + 56     goal_id : {
    + 57       stamp : {
    + 58         secs : 0,
    + 59         nsecs : 0
    + 60       },
    + 61       id : this.goalID
    + 62     },
    + 63     goal : this.goalMessage
    + 64   });
    + 65 
    + 66   this.on('status', function(status) {
    + 67     this.status = status;
    + 68   });
    + 69 
    + 70   this.on('result', function(result) {
    + 71     this.isFinished = true;
    + 72     this.result = result;
    + 73   });
    + 74 
    + 75   this.on('feedback', function(feedback) {
    + 76     this.feedback = feedback;
    + 77   });
    + 78 
    + 79   // add the goal
    + 80   this.actionClient.goals[this.goalID] = this;
    + 81 
    + 82 };
    + 83 ROSLIB.Goal.prototype.__proto__ = EventEmitter2.prototype;
    + 84 
    \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html index ff0e507b2..71f8a5595 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html @@ -64,5 +64,4 @@ 57 }); 58 }; 59 }; - 60 ROSLIB.Param.prototype.__proto__ = EventEmitter2.prototype; - 61 \ No newline at end of file + 60 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html index 5002fe21a..1334bd854 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html @@ -16,229 +16,231 @@ 9 * * 'error' - there was an error with ROS 10 * * 'connection' - connected to the WebSocket server 11 * * 'close' - disconnected to the WebSocket server - 12 * - 13 * @constructor - 14 * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. - 15 */ - 16 ROSLIB.Ros = function(url) { - 17 var ros = this; - 18 ros.socket = null; - 19 - 20 /** - 21 * Emits a 'connection' event on WebSocket connection. - 22 * - 23 * @param event - the argument to emit with the event. - 24 */ - 25 function onOpen(event) { - 26 ros.emit('connection', event); - 27 }; - 28 - 29 /** - 30 * Emits a 'close' event on WebSocket disconnection. - 31 * - 32 * @param event - the argument to emit with the event. - 33 */ - 34 function onClose(event) { - 35 ros.emit('close', event); - 36 }; - 37 - 38 /** - 39 * Emits an 'error' event whenever there was an error. - 40 * - 41 * @param event - the argument to emit with the event. - 42 */ - 43 function onError(event) { - 44 ros.emit('error', event); - 45 }; - 46 - 47 /** - 48 * If a message was compressed as a PNG image (a compression hack since gzipping over WebSockets - 49 * is not supported yet), this function places the "image" in a canvas element then decodes the - 50 * "image" as a Base64 string. - 51 * - 52 * @param data - object containing the PNG data. - 53 * @param callback - function with params: - 54 * * data - the uncompressed data - 55 */ - 56 function decompressPng(data, callback) { - 57 // Uncompresses the data before sending it through (use image/canvas to do so). - 58 var image = new Image(); - 59 // When the image loads, extracts the raw data (JSON message). - 60 image.onload = function() { - 61 // Creates a local canvas to draw on. - 62 var canvas = document.createElement('canvas'); - 63 var context = canvas.getContext('2d'); - 64 - 65 // Sets width and height. - 66 canvas.width = image.width; - 67 canvas.height = image.height; - 68 - 69 // Puts the data into the image. - 70 context.drawImage(image, 0, 0); - 71 // Grabs the raw, uncompressed data. - 72 var imageData = context.getImageData(0, 0, image.width, image.height).data; - 73 - 74 // Constructs the JSON. - 75 var jsonData = ''; - 76 for ( var i = 0; i < imageData.length; i += 4) { - 77 // RGB - 78 jsonData += String.fromCharCode(imageData[i], imageData[i + 1], imageData[i + 2]); - 79 } - 80 var decompressedData = JSON.parse(jsonData); - 81 callback(decompressedData); - 82 }; - 83 // Sends the image data to load. - 84 image.src = 'data:image/png;base64,' + data.data; - 85 } - 86 - 87 /** - 88 * Parses message responses from rosbridge and sends to the appropriate topic, service, or param. - 89 * - 90 * @param message - the raw JSON message from rosbridge. - 91 */ - 92 function onMessage(message) { - 93 function handleMessage(message) { - 94 if (message.op === 'publish') { - 95 ros.emit(message.topic, message.msg); - 96 } else if (message.op === 'service_response') { - 97 ros.emit(message.id, message.values); - 98 } - 99 }; -100 -101 var data = JSON.parse(message.data); -102 if (data.op === 'png') { -103 decompressPng(data, function(decompressedData) { -104 handleMessage(decompressedData); -105 }); -106 } else { -107 handleMessage(data); -108 } -109 }; -110 -111 /** -112 * Connect to the specified WebSocket. -113 * -114 * @param url - WebSocket URL for Rosbridge -115 */ -116 ros.connect = function(url) { -117 ros.socket = new WebSocket(url); -118 ros.socket.onopen = onOpen; -119 ros.socket.onclose = onClose; -120 ros.socket.onerror = onError; -121 ros.socket.onmessage = onMessage; -122 }; -123 -124 /** -125 * Disconnect from the WebSocket server. -126 */ -127 ros.close = function() { -128 if (ros.socket) { -129 ros.socket.close(); -130 } -131 }; -132 -133 /** -134 * Sends an authorization request to the server. -135 * -136 * @param mac - MAC (hash) string given by the trusted source. -137 * @param client - IP of the client. -138 * @param dest - IP of the destination. -139 * @param rand - Random string given by the trusted source. -140 * @param t - Time of the authorization request. -141 * @param level - User level as a string given by the client. -142 * @param end - End time of the client's session. -143 */ -144 ros.authenticate = function(mac, client, dest, rand, t, level, end) { -145 // create the request -146 var auth = { -147 op : 'auth', -148 mac : mac, -149 client : client, -150 dest : dest, -151 rand : rand, -152 t : t, -153 level : level, -154 end : end -155 }; -156 // send the request -157 callOnConnection(auth); -158 }; -159 -160 /** -161 * Sends the message over the WebSocket, but queues the message up if not yet connected. -162 */ -163 ros.callOnConnection = function(message) { -164 var messageJson = JSON.stringify(message); -165 -166 if (ros.socket.readyState !== WebSocket.OPEN) { -167 ros.once('connection', function() { -168 ros.socket.send(messageJson); -169 }); -170 } else { -171 ros.socket.send(messageJson); -172 } -173 }; -174 -175 /** -176 * Retrieves list of topics in ROS as an array. -177 * -178 * @param callback function with params: -179 * * topics - Array of topic names -180 */ -181 ros.getTopics = function(callback) { -182 var topicsClient = new ROSLIB.Service({ -183 name : '/rosapi/topics', -184 serviceType : 'rosapi/Topics' -185 }); -186 -187 var request = new ROSLIB.ServiceRequest(); + 12 * * <topicName> - a message came from rosbridge with the given topic name + 13 * * <serviceID> - a service response came from rosbridge with the given ID + 14 * + 15 * @constructor + 16 * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. + 17 */ + 18 ROSLIB.Ros = function(url) { + 19 var ros = this; + 20 ros.socket = null; + 21 + 22 /** + 23 * Emits a 'connection' event on WebSocket connection. + 24 * + 25 * @param event - the argument to emit with the event. + 26 */ + 27 function onOpen(event) { + 28 ros.emit('connection', event); + 29 }; + 30 + 31 /** + 32 * Emits a 'close' event on WebSocket disconnection. + 33 * + 34 * @param event - the argument to emit with the event. + 35 */ + 36 function onClose(event) { + 37 ros.emit('close', event); + 38 }; + 39 + 40 /** + 41 * Emits an 'error' event whenever there was an error. + 42 * + 43 * @param event - the argument to emit with the event. + 44 */ + 45 function onError(event) { + 46 ros.emit('error', event); + 47 }; + 48 + 49 /** + 50 * If a message was compressed as a PNG image (a compression hack since gzipping over WebSockets + 51 * is not supported yet), this function places the "image" in a canvas element then decodes the + 52 * "image" as a Base64 string. + 53 * + 54 * @param data - object containing the PNG data. + 55 * @param callback - function with params: + 56 * * data - the uncompressed data + 57 */ + 58 function decompressPng(data, callback) { + 59 // Uncompresses the data before sending it through (use image/canvas to do so). + 60 var image = new Image(); + 61 // When the image loads, extracts the raw data (JSON message). + 62 image.onload = function() { + 63 // Creates a local canvas to draw on. + 64 var canvas = document.createElement('canvas'); + 65 var context = canvas.getContext('2d'); + 66 + 67 // Sets width and height. + 68 canvas.width = image.width; + 69 canvas.height = image.height; + 70 + 71 // Puts the data into the image. + 72 context.drawImage(image, 0, 0); + 73 // Grabs the raw, uncompressed data. + 74 var imageData = context.getImageData(0, 0, image.width, image.height).data; + 75 + 76 // Constructs the JSON. + 77 var jsonData = ''; + 78 for ( var i = 0; i < imageData.length; i += 4) { + 79 // RGB + 80 jsonData += String.fromCharCode(imageData[i], imageData[i + 1], imageData[i + 2]); + 81 } + 82 var decompressedData = JSON.parse(jsonData); + 83 callback(decompressedData); + 84 }; + 85 // Sends the image data to load. + 86 image.src = 'data:image/png;base64,' + data.data; + 87 } + 88 + 89 /** + 90 * Parses message responses from rosbridge and sends to the appropriate topic, service, or param. + 91 * + 92 * @param message - the raw JSON message from rosbridge. + 93 */ + 94 function onMessage(message) { + 95 function handleMessage(message) { + 96 if (message.op === 'publish') { + 97 ros.emit(message.topic, message.msg); + 98 } else if (message.op === 'service_response') { + 99 ros.emit(message.id, message.values); +100 } +101 }; +102 +103 var data = JSON.parse(message.data); +104 if (data.op === 'png') { +105 decompressPng(data, function(decompressedData) { +106 handleMessage(decompressedData); +107 }); +108 } else { +109 handleMessage(data); +110 } +111 }; +112 +113 /** +114 * Connect to the specified WebSocket. +115 * +116 * @param url - WebSocket URL for Rosbridge +117 */ +118 ros.connect = function(url) { +119 ros.socket = new WebSocket(url); +120 ros.socket.onopen = onOpen; +121 ros.socket.onclose = onClose; +122 ros.socket.onerror = onError; +123 ros.socket.onmessage = onMessage; +124 }; +125 +126 /** +127 * Disconnect from the WebSocket server. +128 */ +129 ros.close = function() { +130 if (ros.socket) { +131 ros.socket.close(); +132 } +133 }; +134 +135 /** +136 * Sends an authorization request to the server. +137 * +138 * @param mac - MAC (hash) string given by the trusted source. +139 * @param client - IP of the client. +140 * @param dest - IP of the destination. +141 * @param rand - Random string given by the trusted source. +142 * @param t - Time of the authorization request. +143 * @param level - User level as a string given by the client. +144 * @param end - End time of the client's session. +145 */ +146 ros.authenticate = function(mac, client, dest, rand, t, level, end) { +147 // create the request +148 var auth = { +149 op : 'auth', +150 mac : mac, +151 client : client, +152 dest : dest, +153 rand : rand, +154 t : t, +155 level : level, +156 end : end +157 }; +158 // send the request +159 callOnConnection(auth); +160 }; +161 +162 /** +163 * Sends the message over the WebSocket, but queues the message up if not yet connected. +164 */ +165 ros.callOnConnection = function(message) { +166 var messageJson = JSON.stringify(message); +167 +168 if (ros.socket.readyState !== WebSocket.OPEN) { +169 ros.once('connection', function() { +170 ros.socket.send(messageJson); +171 }); +172 } else { +173 ros.socket.send(messageJson); +174 } +175 }; +176 +177 /** +178 * Retrieves list of topics in ROS as an array. +179 * +180 * @param callback function with params: +181 * * topics - Array of topic names +182 */ +183 ros.getTopics = function(callback) { +184 var topicsClient = new ROSLIB.Service({ +185 name : '/rosapi/topics', +186 serviceType : 'rosapi/Topics' +187 }); 188 -189 topicsClient.callService(request, function(result) { -190 callback(result.topics); -191 }); -192 }; -193 -194 /** -195 * Retrieves list of active service names in ROS. -196 * -197 * @param callback - function with the following params: -198 * * services - array of service names -199 */ -200 ros.getServices = function(callback) { -201 var servicesClient = new ROSLIB.Service({ -202 name : '/rosapi/services', -203 serviceType : 'rosapi/Services' -204 }); -205 -206 var request = new ROSLIB.ServiceRequest(); +189 var request = new ROSLIB.ServiceRequest(); +190 +191 topicsClient.callService(request, function(result) { +192 callback(result.topics); +193 }); +194 }; +195 +196 /** +197 * Retrieves list of active service names in ROS. +198 * +199 * @param callback - function with the following params: +200 * * services - array of service names +201 */ +202 ros.getServices = function(callback) { +203 var servicesClient = new ROSLIB.Service({ +204 name : '/rosapi/services', +205 serviceType : 'rosapi/Services' +206 }); 207 -208 servicesClient.callService(request, function(result) { -209 callback(result.services); -210 }); -211 }; -212 -213 /** -214 * Retrieves list of param names from the ROS Parameter Server. -215 * -216 * @param callback function with params: -217 * * params - array of param names. -218 */ -219 ros.getParams = function(callback) { -220 var paramsClient = new ROSLIB.Service({ -221 name : '/rosapi/get_param_names', -222 serviceType : 'rosapi/GetParamNames' -223 }); -224 -225 var request = new ROSLIB.ServiceRequest(); -226 paramsClient.callService(request, function(result) { -227 callback(result.names); -228 }); -229 }; -230 -231 // begin by checking if a URL was given -232 if (url) { -233 ros.connect(url); -234 } -235 }; -236 ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; -237 \ No newline at end of file +208 var request = new ROSLIB.ServiceRequest(); +209 +210 servicesClient.callService(request, function(result) { +211 callback(result.services); +212 }); +213 }; +214 +215 /** +216 * Retrieves list of param names from the ROS Parameter Server. +217 * +218 * @param callback function with params: +219 * * params - array of param names. +220 */ +221 ros.getParams = function(callback) { +222 var paramsClient = new ROSLIB.Service({ +223 name : '/rosapi/get_param_names', +224 serviceType : 'rosapi/GetParamNames' +225 }); +226 +227 var request = new ROSLIB.ServiceRequest(); +228 paramsClient.callService(request, function(result) { +229 callback(result.names); +230 }); +231 }; +232 +233 // begin by checking if a URL was given +234 if (url) { +235 ros.connect(url); +236 } +237 }; +238 ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; +239 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html index ecded7fb2..b111245dd 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html @@ -55,5 +55,4 @@ 48 ros.callOnConnection(call); 49 }; 50 }; - 51 ROSLIB.Service.prototype.__proto__ = EventEmitter2.prototype; - 52 \ No newline at end of file + 51 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html index f7d46dfe9..a2210fdf3 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html @@ -11,135 +11,139 @@ 4 5 /** 6 * Publish and/or subscribe to a topic in ROS. - 7 * - 8 * @constructor - 9 * @param options - object with following keys: - 10 * * ros - the ROSLIB.Ros connection handle - 11 * * name - the topic name, like /cmd_vel - 12 * * messageType - the message type, like 'std_msgs/String' - 13 * * compression - the type of compression to use, like 'png' - 14 * * throttle_rate - the rate at which to throttle the topics - 15 */ - 16 ROSLIB.Topic = function(options) { - 17 var topic = this; - 18 options = options || {}; - 19 topic.ros = options.ros; - 20 topic.name = options.name; - 21 topic.messageType = options.messageType; - 22 topic.isAdvertised = false; - 23 topic.compression = options.compression || 'none'; - 24 topic.throttle_rate = options.throttle_rate || 0; - 25 - 26 // Check for valid compression types - 27 if (topic.compression && topic.compression !== 'png' && topic.compression !== 'none') { - 28 topic.emit('warning', topic.compression - 29 + ' compression is not supported. No comression will be used.'); - 30 } - 31 - 32 // Check if throttle rate is negative - 33 if (topic.throttle_rate < 0) { - 34 topic.emit('warning', topic.throttle_rate + ' is not allowed. Set to 0'); - 35 topic.throttle_rate = 0; - 36 } - 37 - 38 /** - 39 * Every time a message is published for the given topic, the callback - 40 * will be called with the message object. - 41 * - 42 * @param callback - function with the following params: - 43 * * message - the published message - 44 */ - 45 topic.subscribe = function(callback) { - 46 topic.on('message', function(message) { - 47 callback(message); - 48 }); - 49 - 50 ros.on(topic.name, function(data) { - 51 var message = new ROSLIB.Message(data); - 52 topic.emit('message', message); - 53 }); - 54 - 55 ros.idCounter++; - 56 var subscribeId = 'subscribe:' + topic.name + ':' + ros.idCounter; - 57 var call = { - 58 op : 'subscribe', - 59 id : subscribeId, - 60 type : topic.messageType, - 61 topic : topic.name, - 62 compression : topic.compression, - 63 throttle_rate : topic.throttle_rate - 64 }; - 65 - 66 ros.callOnConnection(call); - 67 }; - 68 - 69 /** - 70 * Unregisters as a subscriber for the topic. Unsubscribing will remove - 71 * all subscribe callbacks. - 72 */ - 73 topic.unsubscribe = function() { - 74 ros.removeAllListeners([ topic.name ]); - 75 ros.idCounter++; - 76 var unsubscribeId = 'unsubscribe:' + topic.name + ':' + ros.idCounter; - 77 var call = { - 78 op : 'unsubscribe', - 79 id : unsubscribeId, - 80 topic : topic.name - 81 }; - 82 ros.callOnConnection(call); - 83 }; - 84 - 85 /** - 86 * Registers as a publisher for the topic. - 87 */ - 88 topic.advertise = function() { - 89 ros.idCounter++; - 90 var advertiseId = 'advertise:' + topic.name + ':' + ros.idCounter; - 91 var call = { - 92 op : 'advertise', - 93 id : advertiseId, - 94 type : topic.messageType, - 95 topic : topic.name - 96 }; - 97 ros.callOnConnection(call); - 98 topic.isAdvertised = true; - 99 }; -100 -101 /** -102 * Unregisters as a publisher for the topic. -103 */ -104 topic.unadvertise = function() { -105 ros.idCounter++; -106 var unadvertiseId = 'unadvertise:' + topic.name + ':' + ros.idCounter; -107 var call = { -108 op : 'unadvertise', -109 id : unadvertiseId, -110 topic : topic.name -111 }; -112 ros.callOnConnection(call); -113 topic.isAdvertised = false; -114 }; -115 -116 /** -117 * Publish the message. -118 * -119 * @param message - A ROSLIB.Message object. -120 */ -121 topic.publish = function(message) { -122 if (!topic.isAdvertised) { -123 topic.advertise(); -124 } -125 -126 ros.idCounter++; -127 var publishId = 'publish:' + topic.name + ':' + ros.idCounter; -128 var call = { -129 op : 'publish', -130 id : publishId, -131 topic : topic.name, -132 msg : message -133 }; -134 ros.callOnConnection(call); -135 }; -136 }; -137 ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; -138 \ No newline at end of file + 7 * + 8 * Emits the following events: + 9 * * 'warning' - if there are any warning during the Topic creation + 10 * * 'message' - the message data from rosbridge + 11 * + 12 * @constructor + 13 * @param options - object with following keys: + 14 * * ros - the ROSLIB.Ros connection handle + 15 * * name - the topic name, like /cmd_vel + 16 * * messageType - the message type, like 'std_msgs/String' + 17 * * compression - the type of compression to use, like 'png' + 18 * * throttle_rate - the rate at which to throttle the topics + 19 */ + 20 ROSLIB.Topic = function(options) { + 21 var topic = this; + 22 options = options || {}; + 23 topic.ros = options.ros; + 24 topic.name = options.name; + 25 topic.messageType = options.messageType; + 26 topic.isAdvertised = false; + 27 topic.compression = options.compression || 'none'; + 28 topic.throttle_rate = options.throttle_rate || 0; + 29 + 30 // Check for valid compression types + 31 if (topic.compression && topic.compression !== 'png' && topic.compression !== 'none') { + 32 topic.emit('warning', topic.compression + 33 + ' compression is not supported. No comression will be used.'); + 34 } + 35 + 36 // Check if throttle rate is negative + 37 if (topic.throttle_rate < 0) { + 38 topic.emit('warning', topic.throttle_rate + ' is not allowed. Set to 0'); + 39 topic.throttle_rate = 0; + 40 } + 41 + 42 /** + 43 * Every time a message is published for the given topic, the callback + 44 * will be called with the message object. + 45 * + 46 * @param callback - function with the following params: + 47 * * message - the published message + 48 */ + 49 topic.subscribe = function(callback) { + 50 topic.on('message', function(message) { + 51 callback(message); + 52 }); + 53 + 54 ros.on(topic.name, function(data) { + 55 var message = new ROSLIB.Message(data); + 56 topic.emit('message', message); + 57 }); + 58 + 59 ros.idCounter++; + 60 var subscribeId = 'subscribe:' + topic.name + ':' + ros.idCounter; + 61 var call = { + 62 op : 'subscribe', + 63 id : subscribeId, + 64 type : topic.messageType, + 65 topic : topic.name, + 66 compression : topic.compression, + 67 throttle_rate : topic.throttle_rate + 68 }; + 69 + 70 ros.callOnConnection(call); + 71 }; + 72 + 73 /** + 74 * Unregisters as a subscriber for the topic. Unsubscribing will remove + 75 * all subscribe callbacks. + 76 */ + 77 topic.unsubscribe = function() { + 78 ros.removeAllListeners([ topic.name ]); + 79 ros.idCounter++; + 80 var unsubscribeId = 'unsubscribe:' + topic.name + ':' + ros.idCounter; + 81 var call = { + 82 op : 'unsubscribe', + 83 id : unsubscribeId, + 84 topic : topic.name + 85 }; + 86 ros.callOnConnection(call); + 87 }; + 88 + 89 /** + 90 * Registers as a publisher for the topic. + 91 */ + 92 topic.advertise = function() { + 93 ros.idCounter++; + 94 var advertiseId = 'advertise:' + topic.name + ':' + ros.idCounter; + 95 var call = { + 96 op : 'advertise', + 97 id : advertiseId, + 98 type : topic.messageType, + 99 topic : topic.name +100 }; +101 ros.callOnConnection(call); +102 topic.isAdvertised = true; +103 }; +104 +105 /** +106 * Unregisters as a publisher for the topic. +107 */ +108 topic.unadvertise = function() { +109 ros.idCounter++; +110 var unadvertiseId = 'unadvertise:' + topic.name + ':' + ros.idCounter; +111 var call = { +112 op : 'unadvertise', +113 id : unadvertiseId, +114 topic : topic.name +115 }; +116 ros.callOnConnection(call); +117 topic.isAdvertised = false; +118 }; +119 +120 /** +121 * Publish the message. +122 * +123 * @param message - A ROSLIB.Message object. +124 */ +125 topic.publish = function(message) { +126 if (!topic.isAdvertised) { +127 topic.advertise(); +128 } +129 +130 ros.idCounter++; +131 var publishId = 'publish:' + topic.name + ':' + ros.idCounter; +132 var call = { +133 op : 'publish', +134 id : publishId, +135 topic : topic.name, +136 msg : message +137 }; +138 ros.callOnConnection(call); +139 }; +140 }; +141 ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; +142 \ No newline at end of file diff --git a/examples/fibonacci.html b/examples/fibonacci.html new file mode 100644 index 000000000..c3e7b0d21 --- /dev/null +++ b/examples/fibonacci.html @@ -0,0 +1,58 @@ + + + + + + + + + + + +

    Fibonacci ActionClient Example

    +

    Run the following commands in the terminal then refresh this page. Check the JavaScript + console for the output.

    +
      +
    1. roscore
    2. +
    3. rosrun actionlib_tutorials fibonacci_server
    4. +
    5. roslaunch rosbridge_server rosbridge_websocket.launch
    6. +
    + + \ No newline at end of file diff --git a/src/actionlib/ActionClient.js b/src/actionlib/ActionClient.js index 72e99f740..cc7eec9ed 100644 --- a/src/actionlib/ActionClient.js +++ b/src/actionlib/ActionClient.js @@ -1,79 +1,97 @@ -(function (root, factory) { - if(typeof define === 'function' && define.amd) { - define(['eventemitter2'],factory); - } - else { - root.ActionClient = factory(root.EventEmitter2); - } -}(this, function(EventEmitter2) { - -var ActionClient = function(options) { - var actionClient = this; +/** + * @author Russell Toris - rctoris@wpi.edu + */ + +/** + * An actionlib action client. + * + * Emits the following events: + * * 'timeout' - if a timeout occurred while sending a goal + * * 'status' - the status messages received from the action server + * * 'feedback' - the feedback messages received from the action server + * * 'result' - the result returned from the action server + * + * @constructor + * @param options - object with following keys: + * * ros - the ROSLIB.Ros connection handle + * * serverName - the action server name, like /fibonacci + * * actionName - the action message name, like 'actionlib_tutorials/FibonacciAction' + * * timeout - the timeout length when connecting to the action server + */ +ROSLIB.ActionClient = function(options) { + var that = this; options = options || {}; - actionClient.ros = options.ros; - actionClient.serverName = options.serverName; - actionClient.actionName = options.actionName; - actionClient.timeout = options.timeout; - actionClient.goals = {}; + this.ros = options.ros; + this.serverName = options.serverName; + this.actionName = options.actionName; + this.timeout = options.timeout; + this.goals = {}; - actionClient.goalTopic = new actionClient.ros.Topic({ - name : actionClient.serverName + '/goal' - , messageType : actionClient.actionName + 'Goal' - }); - actionClient.goalTopic.advertise(); + // flag to check if a status has been received + var receivedStatus = false; - actionClient.cancelTopic = new actionClient.ros.Topic({ - name : actionClient.serverName + '/cancel' - , messageType : 'actionlib_msgs/GoalID' + // create the topics associated with actionlib + var feedbackListener = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/feedback', + messageType : this.actionName + 'Feedback' }); - actionClient.cancelTopic.advertise(); - - var receivedStatus = false; - var statusListener = new actionClient.ros.Topic({ - name : actionClient.serverName + '/status' - , messageType : 'actionlib_msgs/GoalStatusArray' + var statusListener = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/status', + messageType : 'actionlib_msgs/GoalStatusArray' + }); + var resultListener = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/result', + messageType : this.actionName + 'Result' + }); + this.goalTopic = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/goal', + messageType : this.actionName + 'Goal' + }); + this.cancelTopic = new ROSLIB.Topic({ + ros : this.ros, + name : this.serverName + '/cancel', + messageType : 'actionlib_msgs/GoalID' }); - statusListener.subscribe(function (statusMessage) { - receivedStatus = true; + /** + * Cancel all goals associated with this ActionClient. + */ + this.cancel = function() { + var cancelMessage = new ROSLIB.Message({}); + this.cancelTopic.publish(cancelMessage); + }; + + // advertise the goal and cancel topics + this.goalTopic.advertise(); + this.cancelTopic.advertise(); + + // subscribe to the status topic + statusListener.subscribe(function(statusMessage) { + receivedStatus = true; statusMessage.status_list.forEach(function(status) { - var goal = actionClient.goals[status.goal_id.id]; + var goal = that.goals[status.goal_id.id]; if (goal) { goal.emit('status', status); } }); }); - // If timeout specified, emit a 'timeout' event if the ActionServer does not - // respond before the timeout. - if (actionClient.timeout) { - setTimeout(function() { - if (!receivedStatus) { - actionClient.emit('timeout'); - } - }, actionClient.timeout); - } - - // Subscribe to the feedback, and result topics - var feedbackListener = new actionClient.ros.Topic({ - name : actionClient.serverName + '/feedback' - , messageType : actionClient.actionName + 'Feedback' - }); - feedbackListener.subscribe(function (feedbackMessage) { - var goal = actionClient.goals[feedbackMessage.status.goal_id.id]; - + // subscribe the the feedback topic + feedbackListener.subscribe(function(feedbackMessage) { + var goal = that.goals[feedbackMessage.status.goal_id.id]; if (goal) { goal.emit('status', feedbackMessage.status); goal.emit('feedback', feedbackMessage.feedback); } }); - var resultListener = new actionClient.ros.Topic({ - name : actionClient.serverName + '/result' - , messageType : actionClient.actionName + 'Result' - }); - resultListener.subscribe(function (resultMessage) { - var goal = actionClient.goals[resultMessage.status.goal_id.id]; + // subscribe to the result topic + resultListener.subscribe(function(resultMessage) { + var goal = that.goals[resultMessage.status.goal_id.id]; if (goal) { goal.emit('status', resultMessage.status); @@ -81,69 +99,13 @@ var ActionClient = function(options) { } }); - actionClient.cancel = function() { - var cancelMessage = new actionClient.ros.Message({}); - actionClient.cancelTopic.publish(cancelMessage); - }; - - actionClient.Goal = function(goalMsg) { - var goal = this; - - goal.isFinished = false; - goal.status; - goal.result; - goal.feedback; - - var date = new Date(); - goal.goalId = 'goal_' + Math.random() + "_" + date.getTime(); - goal.goalMessage = new actionClient.ros.Message({ - goal_id : { - stamp: { - secs : 0 - , nsecs : 0 - } - , id: goal.goalId - } - , goal: goalMsg - }); - - goal.on('status', function(status) { - goal.status = status; - }); - - goal.on('result', function(result) { - goal.isFinished = true; - goal.result = result; - }); - - goal.on('feedback', function(feedback) { - goal.feedback = feedback; - }); - - actionClient.goals[goal.goalId] = this; - - goal.send = function(timeout) { - actionClient.goalTopic.publish(goal.goalMessage); - if (timeout) { - setTimeout(function() { - if (!goal.isFinished) { - goal.emit('timeout'); - } - }, timeout); + // If timeout specified, emit a 'timeout' event if the action server does not respond + if (this.timeout) { + setTimeout(function() { + if (!receivedStatus) { + that.emit('timeout'); } - }; - - goal.cancel = function() { - var cancelMessage = new actionClient.ros.Message({ - id: goal.goalId - }); - actionClient.cancelTopic.publish(cancelMessage); - }; - }; - actionClient.Goal.prototype.__proto__ = EventEmitter2.prototype; - + }, this.timeout); + } }; -ActionClient.prototype.__proto__ = EventEmitter2.prototype; -return ActionClient; -} -)); +ROSLIB.ActionClient.prototype.__proto__ = EventEmitter2.prototype; diff --git a/src/actionlib/Goal.js b/src/actionlib/Goal.js new file mode 100644 index 000000000..696e2057b --- /dev/null +++ b/src/actionlib/Goal.js @@ -0,0 +1,83 @@ +/** + * @author Russell Toris - rctoris@wpi.edu + */ + +/** + * An actionlib goal that is associated with an action server. + * + * Emits the following events: + * * 'timeout' - if a timeout occurred while sending a goal + * + * @constructor + * @param object with following keys: + * * actionClient - the ROSLIB.ActionClient to use with this goal + * * goalMessage - The JSON object containing the goal for the action server + */ + +ROSLIB.Goal = function(options) { + var that = this; + this.actionClient = options.actionClient; + this.goalMessage = options.goalMessage; + this.isFinished = false; + + // used to create random IDs + var date = new Date(); + + /** + * Send the goal to the action server. + * + * @param timeout (optional) - a timeout length for the goal's result + */ + this.send = function(timeout) { + that.actionClient.goalTopic.publish(that.goalMessage); + if (timeout) { + setTimeout(function() { + if (!that.isFinished) { + that.emit('timeout'); + } + }, timeout); + } + }; + + /** + * Cancel the current this. + */ + this.cancel = function() { + var cancelMessage = new ROSLIB.Message({ + id : that.goalID + }); + that.actionClient.cancelTopic.publish(cancelMessage); + }; + + // create a random ID + this.goalID = 'goal_' + Math.random() + "_" + date.getTime(); + // fill in the goal message + this.goalMessage = new ROSLIB.Message({ + goal_id : { + stamp : { + secs : 0, + nsecs : 0 + }, + id : this.goalID + }, + goal : this.goalMessage + }); + + this.on('status', function(status) { + this.status = status; + }); + + this.on('result', function(result) { + this.isFinished = true; + this.result = result; + }); + + this.on('feedback', function(feedback) { + this.feedback = feedback; + }); + + // add the goal + this.actionClient.goals[this.goalID] = this; + +}; +ROSLIB.Goal.prototype.__proto__ = EventEmitter2.prototype; diff --git a/utils/build.xml b/utils/build.xml index 5c31531bc..4236a7f15 100644 --- a/utils/build.xml +++ b/utils/build.xml @@ -50,7 +50,7 @@ - ${js.min}created. + JSDOC created. Date: Fri, 15 Mar 2013 14:44:34 -0700 Subject: [PATCH 2/3] that=this used to reduce jsdoc warnings --- build/roslib.js | 194 +++++----- build/roslib.min.js | 2 +- doc/files.html | 2 +- doc/index.html | 2 +- doc/symbols/ROSLIB.ActionClient.html | 2 +- doc/symbols/ROSLIB.Goal.html | 2 +- doc/symbols/ROSLIB.Message.html | 2 +- doc/symbols/ROSLIB.Param.html | 116 +++++- doc/symbols/ROSLIB.Ros.html | 345 +++++++++++++++++- doc/symbols/ROSLIB.Service.html | 77 +++- doc/symbols/ROSLIB.ServiceRequest.html | 2 +- doc/symbols/ROSLIB.ServiceResponse.html | 2 +- doc/symbols/ROSLIB.Topic.html | 221 ++++++++++- doc/symbols/_global_.html | 2 +- ...oovy_src_roslibjs_src_core_Message.js.html | 4 +- ...groovy_src_roslibjs_src_core_Param.js.html | 12 +- ...S_groovy_src_roslibjs_src_core_Ros.js.html | 52 +-- ...oovy_src_roslibjs_src_core_Service.js.html | 20 +- ...c_roslibjs_src_core_ServiceRequest.js.html | 4 +- ..._roslibjs_src_core_ServiceResponse.js.html | 4 +- ...groovy_src_roslibjs_src_core_Topic.js.html | 98 ++--- examples/simple.html | 2 +- src/core/Message.js | 4 +- src/core/Param.js | 12 +- src/core/Ros.js | 52 +-- src/core/Service.js | 20 +- src/core/ServiceRequest.js | 4 +- src/core/ServiceResponse.js | 4 +- src/core/Topic.js | 98 ++--- 29 files changed, 1056 insertions(+), 305 deletions(-) diff --git a/build/roslib.js b/build/roslib.js index dc0eb7cc6..864e570c9 100644 --- a/build/roslib.js +++ b/build/roslib.js @@ -210,10 +210,10 @@ ROSLIB.Goal.prototype.__proto__ = EventEmitter2.prototype; * @param values - object matching the fields defined in the .msg definition file. */ ROSLIB.Message = function(values) { - var message = this; + var that = this; if (values) { Object.keys(values).forEach(function(name) { - message[name] = values[name]; + that[name] = values[name]; }); } }; @@ -229,9 +229,9 @@ ROSLIB.Message = function(values) { * * name - the param name, like max_vel_x */ ROSLIB.Param = function(options) { - var param = this; + var that = this; options = options || {}; - param.name = options.name; + this.name = options.name; /** * Fetches the value of the param. @@ -239,14 +239,14 @@ ROSLIB.Param = function(options) { * @param callback - function with the following params: * * value - the value of the param from ROS. */ - param.get = function(callback) { + this.get = function(callback) { var paramClient = new ROSLIB.Service({ name : '/rosapi/get_param', serviceType : 'rosapi/GetParam' }); var request = new ROSLIB.ServiceRequest({ - name : param.name, + name : that.name, value : JSON.stringify('') }); @@ -261,14 +261,14 @@ ROSLIB.Param = function(options) { * * @param value - value to set param to. */ - param.set = function(value) { + this.set = function(value) { var paramClient = new ROSLIB.Service({ name : '/rosapi/set_param', serviceType : 'rosapi/SetParam' }); var request = new ROSLIB.ServiceRequest({ - name : param.name, + name : that.name, value : JSON.stringify(value) }); @@ -294,8 +294,8 @@ ROSLIB.Param = function(options) { * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. */ ROSLIB.Ros = function(url) { - var ros = this; - ros.socket = null; + var that = this; + this.socket = null; /** * Emits a 'connection' event on WebSocket connection. @@ -303,7 +303,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onOpen(event) { - ros.emit('connection', event); + that.emit('connection', event); }; /** @@ -312,7 +312,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onClose(event) { - ros.emit('close', event); + that.emit('close', event); }; /** @@ -321,7 +321,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onError(event) { - ros.emit('error', event); + that.emit('error', event); }; /** @@ -372,9 +372,9 @@ ROSLIB.Ros = function(url) { function onMessage(message) { function handleMessage(message) { if (message.op === 'publish') { - ros.emit(message.topic, message.msg); + that.emit(message.topic, message.msg); } else if (message.op === 'service_response') { - ros.emit(message.id, message.values); + that.emit(message.id, message.values); } }; @@ -393,20 +393,20 @@ ROSLIB.Ros = function(url) { * * @param url - WebSocket URL for Rosbridge */ - ros.connect = function(url) { - ros.socket = new WebSocket(url); - ros.socket.onopen = onOpen; - ros.socket.onclose = onClose; - ros.socket.onerror = onError; - ros.socket.onmessage = onMessage; + this.connect = function(url) { + that.socket = new WebSocket(url); + that.socket.onopen = onOpen; + that.socket.onclose = onClose; + that.socket.onerror = onError; + that.socket.onmessage = onMessage; }; /** * Disconnect from the WebSocket server. */ - ros.close = function() { - if (ros.socket) { - ros.socket.close(); + this.close = function() { + if (that.socket) { + that.socket.close(); } }; @@ -421,7 +421,7 @@ ROSLIB.Ros = function(url) { * @param level - User level as a string given by the client. * @param end - End time of the client's session. */ - ros.authenticate = function(mac, client, dest, rand, t, level, end) { + this.authenticate = function(mac, client, dest, rand, t, level, end) { // create the request var auth = { op : 'auth', @@ -440,15 +440,15 @@ ROSLIB.Ros = function(url) { /** * Sends the message over the WebSocket, but queues the message up if not yet connected. */ - ros.callOnConnection = function(message) { + this.callOnConnection = function(message) { var messageJson = JSON.stringify(message); - if (ros.socket.readyState !== WebSocket.OPEN) { - ros.once('connection', function() { - ros.socket.send(messageJson); + if (that.socket.readyState !== WebSocket.OPEN) { + that.once('connection', function() { + that.socket.send(messageJson); }); } else { - ros.socket.send(messageJson); + that.socket.send(messageJson); } }; @@ -458,7 +458,7 @@ ROSLIB.Ros = function(url) { * @param callback function with params: * * topics - Array of topic names */ - ros.getTopics = function(callback) { + this.getTopics = function(callback) { var topicsClient = new ROSLIB.Service({ name : '/rosapi/topics', serviceType : 'rosapi/Topics' @@ -477,7 +477,7 @@ ROSLIB.Ros = function(url) { * @param callback - function with the following params: * * services - array of service names */ - ros.getServices = function(callback) { + this.getServices = function(callback) { var servicesClient = new ROSLIB.Service({ name : '/rosapi/services', serviceType : 'rosapi/Services' @@ -496,7 +496,7 @@ ROSLIB.Ros = function(url) { * @param callback function with params: * * params - array of param names. */ - ros.getParams = function(callback) { + this.getParams = function(callback) { var paramsClient = new ROSLIB.Service({ name : '/rosapi/get_param_names', serviceType : 'rosapi/GetParamNames' @@ -510,7 +510,7 @@ ROSLIB.Ros = function(url) { // begin by checking if a URL was given if (url) { - ros.connect(url); + this.connect(url); } }; ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; @@ -528,11 +528,11 @@ ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' */ ROSLIB.Service = function(options) { - var service = this; + var that = this; options = options || {}; - service.ros = options.ros; - service.name = options.name; - service.serviceType = options.serviceType; + this.ros = options.ros; + this.name = options.name; + this.serviceType = options.serviceType; /** * Calls the service. Returns the service response in the callback. @@ -541,11 +541,11 @@ ROSLIB.Service = function(options) { * @param callback - function with params: * * response - the response from the service request */ - service.callService = function(request, callback) { - ros.idCounter++; - serviceCallId = 'call_service:' + service.name + ':' + ros.idCounter; + this.callService = function(request, callback) { + that.ros.idCounter++; + serviceCallId = 'call_service:' + that.name + ':' + that.ros.idCounter; - ros.once(serviceCallId, function(data) { + that.ros.once(serviceCallId, function(data) { var response = new ROSLIB.ServiceResponse(data); callback(response); }); @@ -558,10 +558,10 @@ ROSLIB.Service = function(options) { var call = { op : 'call_service', id : serviceCallId, - service : service.name, + service : that.name, args : requestValues }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; }; /** @@ -575,10 +575,10 @@ ROSLIB.Service = function(options) { * @param values - object matching the values of the request part from the .srv file. */ ROSLIB.ServiceRequest = function(values) { - var serviceRequest = this; + var that = this; if (values) { Object.keys(values).forEach(function(name) { - serviceRequest[name] = values[name]; + that[name] = values[name]; }); } }; @@ -593,10 +593,10 @@ ROSLIB.ServiceRequest = function(values) { * @param values - object matching the values of the response part from the .srv file. */ ROSLIB.ServiceResponse = function(values) { - var serviceResponse = this; + var that = this; if (values) { Object.keys(values).forEach(function(name) { - serviceResponse[name] = values[name]; + that[name] = values[name]; }); } }; @@ -620,25 +620,25 @@ ROSLIB.ServiceResponse = function(values) { * * throttle_rate - the rate at which to throttle the topics */ ROSLIB.Topic = function(options) { - var topic = this; + var that = this; options = options || {}; - topic.ros = options.ros; - topic.name = options.name; - topic.messageType = options.messageType; - topic.isAdvertised = false; - topic.compression = options.compression || 'none'; - topic.throttle_rate = options.throttle_rate || 0; + this.ros = options.ros; + this.name = options.name; + this.messageType = options.messageType; + this.isAdvertised = false; + this.compression = options.compression || 'none'; + this.throttle_rate = options.throttle_rate || 0; // Check for valid compression types - if (topic.compression && topic.compression !== 'png' && topic.compression !== 'none') { - topic.emit('warning', topic.compression + if (this.compression && this.compression !== 'png' && this.compression !== 'none') { + this.emit('warning', this.compression + ' compression is not supported. No comression will be used.'); } // Check if throttle rate is negative - if (topic.throttle_rate < 0) { - topic.emit('warning', topic.throttle_rate + ' is not allowed. Set to 0'); - topic.throttle_rate = 0; + if (this.throttle_rate < 0) { + this.emit('warning', this.throttle_rate + ' is not allowed. Set to 0'); + this.throttle_rate = 0; } /** @@ -648,75 +648,75 @@ ROSLIB.Topic = function(options) { * @param callback - function with the following params: * * message - the published message */ - topic.subscribe = function(callback) { - topic.on('message', function(message) { + this.subscribe = function(callback) { + that.on('message', function(message) { callback(message); }); - ros.on(topic.name, function(data) { + that.ros.on(that.name, function(data) { var message = new ROSLIB.Message(data); - topic.emit('message', message); + that.emit('message', message); }); - ros.idCounter++; - var subscribeId = 'subscribe:' + topic.name + ':' + ros.idCounter; + that.ros.idCounter++; + var subscribeId = 'subscribe:' + that.name + ':' + that.ros.idCounter; var call = { op : 'subscribe', id : subscribeId, - type : topic.messageType, - topic : topic.name, - compression : topic.compression, - throttle_rate : topic.throttle_rate + type : that.messageType, + topic : that.name, + compression : that.compression, + throttle_rate : that.throttle_rate }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; /** * Unregisters as a subscriber for the topic. Unsubscribing will remove * all subscribe callbacks. */ - topic.unsubscribe = function() { - ros.removeAllListeners([ topic.name ]); - ros.idCounter++; - var unsubscribeId = 'unsubscribe:' + topic.name + ':' + ros.idCounter; + this.unsubscribe = function() { + that.ros.removeAllListeners([ that.name ]); + that.ros.idCounter++; + var unsubscribeId = 'unsubscribe:' + that.name + ':' + that.ros.idCounter; var call = { op : 'unsubscribe', id : unsubscribeId, - topic : topic.name + topic : that.name }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; /** * Registers as a publisher for the topic. */ - topic.advertise = function() { - ros.idCounter++; - var advertiseId = 'advertise:' + topic.name + ':' + ros.idCounter; + this.advertise = function() { + that.ros.idCounter++; + var advertiseId = 'advertise:' + that.name + ':' + that.ros.idCounter; var call = { op : 'advertise', id : advertiseId, - type : topic.messageType, - topic : topic.name + type : that.messageType, + topic : that.name }; - ros.callOnConnection(call); - topic.isAdvertised = true; + that.ros.callOnConnection(call); + that.isAdvertised = true; }; /** * Unregisters as a publisher for the topic. */ - topic.unadvertise = function() { - ros.idCounter++; - var unadvertiseId = 'unadvertise:' + topic.name + ':' + ros.idCounter; + this.unadvertise = function() { + that.ros.idCounter++; + var unadvertiseId = 'unadvertise:' + that.name + ':' + that.ros.idCounter; var call = { op : 'unadvertise', id : unadvertiseId, - topic : topic.name + topic : that.name }; - ros.callOnConnection(call); - topic.isAdvertised = false; + that.ros.callOnConnection(call); + that.isAdvertised = false; }; /** @@ -724,20 +724,20 @@ ROSLIB.Topic = function(options) { * * @param message - A ROSLIB.Message object. */ - topic.publish = function(message) { - if (!topic.isAdvertised) { - topic.advertise(); + this.publish = function(message) { + if (!that.isAdvertised) { + that.advertise(); } - ros.idCounter++; - var publishId = 'publish:' + topic.name + ':' + ros.idCounter; + that.ros.idCounter++; + var publishId = 'publish:' + that.name + ':' + that.ros.idCounter; var call = { op : 'publish', id : publishId, - topic : topic.name, + topic : that.name, msg : message }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; }; ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; diff --git a/build/roslib.min.js b/build/roslib.min.js index d3fc54001..cbbb6cdde 100644 --- a/build/roslib.min.js +++ b/build/roslib.min.js @@ -1 +1 @@ -var ROSLIB=ROSLIB||{REVISION:"1"};ROSLIB.ActionClient=function(b){var c=this;b=b||{};this.ros=b.ros;this.serverName=b.serverName;this.actionName=b.actionName;this.timeout=b.timeout;this.goals={};var a=false;var d=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/feedback",messageType:this.actionName+"Feedback"});var e=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/status",messageType:"actionlib_msgs/GoalStatusArray"});var f=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/result",messageType:this.actionName+"Result"});this.goalTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/goal",messageType:this.actionName+"Goal"});this.cancelTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/cancel",messageType:"actionlib_msgs/GoalID"});this.cancel=function(){var g=new ROSLIB.Message({});this.cancelTopic.publish(g)};this.goalTopic.advertise();this.cancelTopic.advertise();e.subscribe(function(g){a=true;g.status_list.forEach(function(h){var i=c.goals[h.goal_id.id];if(i){i.emit("status",h)}})});d.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("feedback",h.feedback)}});f.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("result",h.result)}});if(this.timeout){setTimeout(function(){if(!a){c.emit("timeout")}},this.timeout)}};ROSLIB.ActionClient.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Goal=function(b){var c=this;this.actionClient=b.actionClient;this.goalMessage=b.goalMessage;this.isFinished=false;var a=new Date();this.send=function(d){c.actionClient.goalTopic.publish(c.goalMessage);if(d){setTimeout(function(){if(!c.isFinished){c.emit("timeout")}},d)}};this.cancel=function(){var d=new ROSLIB.Message({id:c.goalID});c.actionClient.cancelTopic.publish(d)};this.goalID="goal_"+Math.random()+"_"+a.getTime();this.goalMessage=new ROSLIB.Message({goal_id:{stamp:{secs:0,nsecs:0},id:this.goalID},goal:this.goalMessage});this.on("status",function(d){this.status=d});this.on("result",function(d){this.isFinished=true;this.result=d});this.on("feedback",function(d){this.feedback=d});this.actionClient.goals[this.goalID]=this};ROSLIB.Goal.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Message=function(a){var b=this;if(a){Object.keys(a).forEach(function(c){b[c]=a[c]})}};ROSLIB.Param=function(a){var b=this;a=a||{};b.name=a.name;b.get=function(e){var d=new ROSLIB.Service({name:"/rosapi/get_param",serviceType:"rosapi/GetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify("")});d.callService(c,function(f){var g=JSON.parse(f.value);e(g)})};b.set=function(e){var d=new ROSLIB.Service({name:"/rosapi/set_param",serviceType:"rosapi/SetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify(e)});d.callService(c,function(){})}};ROSLIB.Ros=function(d){var c=this;c.socket=null;function b(h){c.emit("connection",h)}function a(h){c.emit("close",h)}function e(h){c.emit("error",h)}function g(h,j){var i=new Image();i.onload=function(){var k=document.createElement("canvas");var m=k.getContext("2d");k.width=i.width;k.height=i.height;m.drawImage(i,0,0);var p=m.getImageData(0,0,i.width,i.height).data;var n="";for(var l=0;l=0){j.cbs.splice(h,1);if(j.cbs.length==0){delete this.frame_infos[i]}this.needUpdate=true}}};var f=d.Pose=function(h,i){this.position=new a;this.orientation=new e;if(h!==undefined){this.position.copy(h)}if(i!==undefined){this.orientation.copy(i)}};f.prototype={constructor:f,copy:function(h){this.position.copy(h.position);this.orientation.copy(h.orientation)}};var c=d.Transform=function(i,h){this.translation=new a;this.rotation=new e;if(i!==undefined){this.translation.copy(i)}if(h!==undefined){this.rotation.copy(h)}};c.prototype={constructor:c,apply:function(h){this.rotation.multiplyVec3(h.position);h.position.add(h.position,this.translation);h.orientation.multiply(this.rotation,h.orientation);return h},applyInverse:function(i){var h=this.rotation.clone().inverse();h.multiplyVec3(i.position);i.position.sub(i.position,this.translation);i.orientation.multiply(h,i.orientation);return i},copy:function(h){this.translation.copy(h.translation);this.rotation.copy(h.rotation)}};var e=d.Quaternion=function(h,k,j,i){this.x=h||0;this.y=k||0;this.z=j||0;this.w=(i!==undefined)?i:1};e.prototype={constructor:e,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;this.w=h.w;return this},inverse:function(){this.conjugate().normalize();return this},conjugate:function(){this.x*=-1;this.y*=-1;this.z*=-1;return this},normalize:function(){var h=Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w);if(h===0){this.x=0;this.y=0;this.z=0;this.w=1}else{h=1/h;this.x=this.x*h;this.y=this.y*h;this.z=this.z*h;this.w=this.w*h}return this},multiply:function(q,p){var n=q.x,m=q.y,l=q.z,o=q.w,j=p.x,i=p.y,h=p.z,k=p.w;this.x=n*k+m*h-l*i+o*j;this.y=-n*h+m*k+l*j+o*i;this.z=n*i-m*j+l*k+o*h;this.w=-n*j-m*i-l*h+o*k;return this},multiplyVec3:function(j,t){if(!t){t=j}var s=j.x,r=j.y,q=j.z,o=this.x,n=this.y,m=this.z,p=this.w;var k=p*s+n*q-m*r,i=p*r+m*s-o*q,h=p*q+o*r-n*s,l=-o*s-n*r-m*q;t.x=k*p+l*-o+i*-m-h*-n;t.y=i*p+l*-n+h*-o-k*-m;t.z=h*p+l*-m+k*-n-i*-o;return t},clone:function(){return new e(this.x,this.y,this.z,this.w)}};var a=d.Vector3=function(h,j,i){this.x=h||0;this.y=j||0;this.z=i||0};a.prototype={constructor:a,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;return this},add:function(i,h){this.x=i.x+h.x;this.y=i.y+h.y;this.z=i.z+h.z;return this},sub:function(i,h){this.x=i.x-h.x;this.y=i.y-h.y;this.z=i.z-h.z;return this},clone:function(){return new a(this.x,this.y,this.z)}};return d})); \ No newline at end of file +var ROSLIB=ROSLIB||{REVISION:"1"};ROSLIB.ActionClient=function(b){var c=this;b=b||{};this.ros=b.ros;this.serverName=b.serverName;this.actionName=b.actionName;this.timeout=b.timeout;this.goals={};var a=false;var d=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/feedback",messageType:this.actionName+"Feedback"});var e=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/status",messageType:"actionlib_msgs/GoalStatusArray"});var f=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/result",messageType:this.actionName+"Result"});this.goalTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/goal",messageType:this.actionName+"Goal"});this.cancelTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/cancel",messageType:"actionlib_msgs/GoalID"});this.cancel=function(){var g=new ROSLIB.Message({});this.cancelTopic.publish(g)};this.goalTopic.advertise();this.cancelTopic.advertise();e.subscribe(function(g){a=true;g.status_list.forEach(function(h){var i=c.goals[h.goal_id.id];if(i){i.emit("status",h)}})});d.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("feedback",h.feedback)}});f.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("result",h.result)}});if(this.timeout){setTimeout(function(){if(!a){c.emit("timeout")}},this.timeout)}};ROSLIB.ActionClient.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Goal=function(b){var c=this;this.actionClient=b.actionClient;this.goalMessage=b.goalMessage;this.isFinished=false;var a=new Date();this.send=function(d){c.actionClient.goalTopic.publish(c.goalMessage);if(d){setTimeout(function(){if(!c.isFinished){c.emit("timeout")}},d)}};this.cancel=function(){var d=new ROSLIB.Message({id:c.goalID});c.actionClient.cancelTopic.publish(d)};this.goalID="goal_"+Math.random()+"_"+a.getTime();this.goalMessage=new ROSLIB.Message({goal_id:{stamp:{secs:0,nsecs:0},id:this.goalID},goal:this.goalMessage});this.on("status",function(d){this.status=d});this.on("result",function(d){this.isFinished=true;this.result=d});this.on("feedback",function(d){this.feedback=d});this.actionClient.goals[this.goalID]=this};ROSLIB.Goal.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Message=function(a){var b=this;if(a){Object.keys(a).forEach(function(c){b[c]=a[c]})}};ROSLIB.Param=function(a){var b=this;a=a||{};this.name=a.name;this.get=function(e){var d=new ROSLIB.Service({name:"/rosapi/get_param",serviceType:"rosapi/GetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify("")});d.callService(c,function(f){var g=JSON.parse(f.value);e(g)})};this.set=function(e){var d=new ROSLIB.Service({name:"/rosapi/set_param",serviceType:"rosapi/SetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify(e)});d.callService(c,function(){})}};ROSLIB.Ros=function(c){var e=this;this.socket=null;function b(h){e.emit("connection",h)}function a(h){e.emit("close",h)}function d(h){e.emit("error",h)}function g(h,j){var i=new Image();i.onload=function(){var k=document.createElement("canvas");var m=k.getContext("2d");k.width=i.width;k.height=i.height;m.drawImage(i,0,0);var p=m.getImageData(0,0,i.width,i.height).data;var n="";for(var l=0;l=0){j.cbs.splice(h,1);if(j.cbs.length==0){delete this.frame_infos[i]}this.needUpdate=true}}};var f=d.Pose=function(h,i){this.position=new a;this.orientation=new e;if(h!==undefined){this.position.copy(h)}if(i!==undefined){this.orientation.copy(i)}};f.prototype={constructor:f,copy:function(h){this.position.copy(h.position);this.orientation.copy(h.orientation)}};var c=d.Transform=function(i,h){this.translation=new a;this.rotation=new e;if(i!==undefined){this.translation.copy(i)}if(h!==undefined){this.rotation.copy(h)}};c.prototype={constructor:c,apply:function(h){this.rotation.multiplyVec3(h.position);h.position.add(h.position,this.translation);h.orientation.multiply(this.rotation,h.orientation);return h},applyInverse:function(i){var h=this.rotation.clone().inverse();h.multiplyVec3(i.position);i.position.sub(i.position,this.translation);i.orientation.multiply(h,i.orientation);return i},copy:function(h){this.translation.copy(h.translation);this.rotation.copy(h.rotation)}};var e=d.Quaternion=function(h,k,j,i){this.x=h||0;this.y=k||0;this.z=j||0;this.w=(i!==undefined)?i:1};e.prototype={constructor:e,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;this.w=h.w;return this},inverse:function(){this.conjugate().normalize();return this},conjugate:function(){this.x*=-1;this.y*=-1;this.z*=-1;return this},normalize:function(){var h=Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w);if(h===0){this.x=0;this.y=0;this.z=0;this.w=1}else{h=1/h;this.x=this.x*h;this.y=this.y*h;this.z=this.z*h;this.w=this.w*h}return this},multiply:function(q,p){var n=q.x,m=q.y,l=q.z,o=q.w,j=p.x,i=p.y,h=p.z,k=p.w;this.x=n*k+m*h-l*i+o*j;this.y=-n*h+m*k+l*j+o*i;this.z=n*i-m*j+l*k+o*h;this.w=-n*j-m*i-l*h+o*k;return this},multiplyVec3:function(j,t){if(!t){t=j}var s=j.x,r=j.y,q=j.z,o=this.x,n=this.y,m=this.z,p=this.w;var k=p*s+n*q-m*r,i=p*r+m*s-o*q,h=p*q+o*r-n*s,l=-o*s-n*r-m*q;t.x=k*p+l*-o+i*-m-h*-n;t.y=i*p+l*-n+h*-o-k*-m;t.z=h*p+l*-m+k*-n-i*-o;return t},clone:function(){return new e(this.x,this.y,this.z,this.w)}};var a=d.Vector3=function(h,j,i){this.x=h||0;this.y=j||0;this.z=i||0};a.prototype={constructor:a,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;return this},add:function(i,h){this.x=i.x+h.x;this.y=i.y+h.y;this.z=i.z+h.z;return this},sub:function(i,h){this.x=i.x-h.x;this.y=i.y-h.y;this.z=i.z-h.z;return this},clone:function(){return new a(this.x,this.y,this.z)}};return d})); \ No newline at end of file diff --git a/doc/files.html b/doc/files.html index 7a98933c3..95532d3b9 100644 --- a/doc/files.html +++ b/doc/files.html @@ -348,7 +348,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) \ No newline at end of file diff --git a/doc/index.html b/doc/index.html index 9bae109e0..59dc2c561 100644 --- a/doc/index.html +++ b/doc/index.html @@ -276,7 +276,7 @@

    ROSLIB.Topic

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    \ No newline at end of file diff --git a/doc/symbols/ROSLIB.ActionClient.html b/doc/symbols/ROSLIB.ActionClient.html index 87aa2655c..2fde3538f 100644 --- a/doc/symbols/ROSLIB.ActionClient.html +++ b/doc/symbols/ROSLIB.ActionClient.html @@ -389,7 +389,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Goal.html b/doc/symbols/ROSLIB.Goal.html index 5dc057c3d..b724b979b 100644 --- a/doc/symbols/ROSLIB.Goal.html +++ b/doc/symbols/ROSLIB.Goal.html @@ -429,7 +429,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Message.html b/doc/symbols/ROSLIB.Message.html index 9fc1928ff..f807e5cf4 100644 --- a/doc/symbols/ROSLIB.Message.html +++ b/doc/symbols/ROSLIB.Message.html @@ -322,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Param.html b/doc/symbols/ROSLIB.Param.html index 1c22ed657..6545d5681 100644 --- a/doc/symbols/ROSLIB.Param.html +++ b/doc/symbols/ROSLIB.Param.html @@ -262,6 +262,42 @@

    + + + + + + + + + + + + + + + + + + + + + + + +
    Method Summary
    Method AttributesMethod Name and Description
      +
    get(callback) +
    +
    Fetches the value of the param.
    +
      +
    set(value) +
    +
    Sets the value of the param in ROS.
    +
    + + + + @@ -312,6 +348,84 @@

    +
    + Method Detail +
    + + +
    + + + get(callback) + +
    +
    + Fetches the value of the param. + + +
    + + + + +
    +
    Parameters:
    + +
    + callback + +
    +
    - function with the following params: + * value - the value of the param from ROS.
    + +
    + + + + + + + + +
    + + +
    + + + set(value) + +
    +
    + Sets the value of the param in ROS. + + +
    + + + + +
    +
    Parameters:
    + +
    + value + +
    +
    - value to set param to.
    + +
    + + + + + + + + + + + @@ -323,7 +437,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Ros.html b/doc/symbols/ROSLIB.Ros.html index 35a07d2c0..3b9cc6bb0 100644 --- a/doc/symbols/ROSLIB.Ros.html +++ b/doc/symbols/ROSLIB.Ros.html @@ -274,6 +274,42 @@

    + +   + +
    authenticate(mac, client, dest, rand, t, level, end) +
    +
    Sends an authorization request to the server.
    + + + + +   + +
    callOnConnection(message) +
    +
    Sends the message over the WebSocket, but queues the message up if not yet connected.
    + + + + +   + +
    close() +
    +
    Disconnect from the WebSocket server.
    + + + + +   + +
    connect(url) +
    +
    Connect to the specified WebSocket.
    + + + <inner>   @@ -285,6 +321,33 @@

    + +   + +
    getParams(callback) +
    +
    Retrieves list of param names from the ROS Parameter Server.
    + + + + +   + +
    getServices(callback) +
    +
    Retrieves list of active service names in ROS.
    + + + + +   + +
    getTopics(callback) +
    +
    Retrieves list of topics in ROS as an array.
    + + + <inner>   @@ -387,6 +450,175 @@

    Method Detail + +
    + + + authenticate(mac, client, dest, rand, t, level, end) + +
    +
    + Sends an authorization request to the server. + + +
    + + + + +
    +
    Parameters:
    + +
    + mac + +
    +
    - MAC (hash) string given by the trusted source.
    + +
    + client + +
    +
    - IP of the client.
    + +
    + dest + +
    +
    - IP of the destination.
    + +
    + rand + +
    +
    - Random string given by the trusted source.
    + +
    + t + +
    +
    - Time of the authorization request.
    + +
    + level + +
    +
    - User level as a string given by the client.
    + +
    + end + +
    +
    - End time of the client's session.
    + +
    + + + + + + + + +
    + + +
    + + + callOnConnection(message) + +
    +
    + Sends the message over the WebSocket, but queues the message up if not yet connected. + + +
    + + + + +
    +
    Parameters:
    + +
    + message + +
    +
    + +
    + + + + + + + + +
    + + +
    + + + close() + +
    +
    + Disconnect from the WebSocket server. + + +
    + + + + + + + + + + + +
    + + +
    + + + connect(url) + +
    +
    + Connect to the specified WebSocket. + + +
    + + + + +
    +
    Parameters:
    + +
    + url + +
    +
    - WebSocket URL for Rosbridge
    + +
    + + + + + + + + +
    +
    <inner> @@ -430,6 +662,117 @@

    +
    + + +
    + + + getParams(callback) + +
    +
    + Retrieves list of param names from the ROS Parameter Server. + + +
    + + + + +
    +
    Parameters:
    + +
    + callback + +
    +
    function with params: + * params - array of param names.
    + +
    + + + + + + + + +
    + + +
    + + + getServices(callback) + +
    +
    + Retrieves list of active service names in ROS. + + +
    + + + + +
    +
    Parameters:
    + +
    + callback + +
    +
    - function with the following params: + * services - array of service names
    + +
    + + + + + + + + +
    + + +
    + + + getTopics(callback) + +
    +
    + Retrieves list of topics in ROS as an array. + + +
    + + + + +
    +
    Parameters:
    + +
    + callback + +
    +
    function with params: + * topics - Array of topic names
    + +
    + + + + + + + +
    @@ -588,7 +931,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Service.html b/doc/symbols/ROSLIB.Service.html index 444965cb9..0454e0573 100644 --- a/doc/symbols/ROSLIB.Service.html +++ b/doc/symbols/ROSLIB.Service.html @@ -262,6 +262,33 @@

    + + + + + + + + + + + + + + + + + + +
    Method Summary
    Method AttributesMethod Name and Description
      +
    callService(request, callback) +
    +
    Calls the service.
    +
    + + + + @@ -311,6 +338,54 @@

    +
    + Method Detail +
    + + +
    + + + callService(request, callback) + +
    +
    + Calls the service. Returns the service response in the callback. + + +
    + + + + +
    +
    Parameters:
    + +
    + request + +
    +
    - the ROSLIB.ServiceRequest to send
    + +
    + callback + +
    +
    - function with params: + * response - the response from the service request
    + +
    + + + + + + + + + + + @@ -322,7 +397,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.ServiceRequest.html b/doc/symbols/ROSLIB.ServiceRequest.html index 95b6809f4..cec4de281 100644 --- a/doc/symbols/ROSLIB.ServiceRequest.html +++ b/doc/symbols/ROSLIB.ServiceRequest.html @@ -322,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.ServiceResponse.html b/doc/symbols/ROSLIB.ServiceResponse.html index c69d8b412..9be064e43 100644 --- a/doc/symbols/ROSLIB.ServiceResponse.html +++ b/doc/symbols/ROSLIB.ServiceResponse.html @@ -322,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Topic.html b/doc/symbols/ROSLIB.Topic.html index ce7941d06..17c2157a8 100644 --- a/doc/symbols/ROSLIB.Topic.html +++ b/doc/symbols/ROSLIB.Topic.html @@ -262,6 +262,70 @@

    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    Method Summary
    Method AttributesMethod Name and Description
      + +
    Registers as a publisher for the topic.
    +
      +
    publish(message) +
    +
    Publish the message.
    +
      +
    subscribe(callback) +
    +
    Every time a message is published for the given topic, the callback +will be called with the message object.
    +
      + +
    Unregisters as a publisher for the topic.
    +
      + +
    Unregisters as a subscriber for the topic.
    +
    + + + + @@ -320,6 +384,161 @@

    +
    + Method Detail +
    + + +
    + + + advertise() + +
    +
    + Registers as a publisher for the topic. + + +
    + + + + + + + + + + + +
    + + +
    + + + publish(message) + +
    +
    + Publish the message. + + +
    + + + + +
    +
    Parameters:
    + +
    + message + +
    +
    - A ROSLIB.Message object.
    + +
    + + + + + + + + +
    + + +
    + + + subscribe(callback) + +
    +
    + Every time a message is published for the given topic, the callback +will be called with the message object. + + +
    + + + + +
    +
    Parameters:
    + +
    + callback + +
    +
    - function with the following params: + * message - the published message
    + +
    + + + + + + + + +
    + + +
    + + + unadvertise() + +
    +
    + Unregisters as a publisher for the topic. + + +
    + + + + + + + + + + + +
    + + +
    + + + unsubscribe() + +
    +
    + Unregisters as a subscriber for the topic. Unsubscribing will remove +all subscribe callbacks. + + +
    + + + + + + + + + + + + + + @@ -331,7 +550,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:29 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/_global_.html b/doc/symbols/_global_.html index 1ef15c8a6..4679fcd4d 100644 --- a/doc/symbols/_global_.html +++ b/doc/symbols/_global_.html @@ -319,7 +319,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:13:28 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT)
    diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html index b238319ea..62faddd27 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html @@ -16,10 +16,10 @@ 9 * @param values - object matching the fields defined in the .msg definition file. 10 */ 11 ROSLIB.Message = function(values) { - 12 var message = this; + 12 var that = this; 13 if (values) { 14 Object.keys(values).forEach(function(name) { - 15 message[name] = values[name]; + 15 that[name] = values[name]; 16 }); 17 } 18 }; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html index 71f8a5595..be5fe0691 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html @@ -17,9 +17,9 @@ 10 * * name - the param name, like max_vel_x 11 */ 12 ROSLIB.Param = function(options) { - 13 var param = this; + 13 var that = this; 14 options = options || {}; - 15 param.name = options.name; + 15 this.name = options.name; 16 17 /** 18 * Fetches the value of the param. @@ -27,14 +27,14 @@ 20 * @param callback - function with the following params: 21 * * value - the value of the param from ROS. 22 */ - 23 param.get = function(callback) { + 23 this.get = function(callback) { 24 var paramClient = new ROSLIB.Service({ 25 name : '/rosapi/get_param', 26 serviceType : 'rosapi/GetParam' 27 }); 28 29 var request = new ROSLIB.ServiceRequest({ - 30 name : param.name, + 30 name : that.name, 31 value : JSON.stringify('') 32 }); 33 @@ -49,14 +49,14 @@ 42 * 43 * @param value - value to set param to. 44 */ - 45 param.set = function(value) { + 45 this.set = function(value) { 46 var paramClient = new ROSLIB.Service({ 47 name : '/rosapi/set_param', 48 serviceType : 'rosapi/SetParam' 49 }); 50 51 var request = new ROSLIB.ServiceRequest({ - 52 name : param.name, + 52 name : that.name, 53 value : JSON.stringify(value) 54 }); 55 diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html index 1334bd854..8a42f63fb 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html @@ -23,8 +23,8 @@ 16 * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. 17 */ 18 ROSLIB.Ros = function(url) { - 19 var ros = this; - 20 ros.socket = null; + 19 var that = this; + 20 this.socket = null; 21 22 /** 23 * Emits a 'connection' event on WebSocket connection. @@ -32,7 +32,7 @@ 25 * @param event - the argument to emit with the event. 26 */ 27 function onOpen(event) { - 28 ros.emit('connection', event); + 28 that.emit('connection', event); 29 }; 30 31 /** @@ -41,7 +41,7 @@ 34 * @param event - the argument to emit with the event. 35 */ 36 function onClose(event) { - 37 ros.emit('close', event); + 37 that.emit('close', event); 38 }; 39 40 /** @@ -50,7 +50,7 @@ 43 * @param event - the argument to emit with the event. 44 */ 45 function onError(event) { - 46 ros.emit('error', event); + 46 that.emit('error', event); 47 }; 48 49 /** @@ -101,9 +101,9 @@ 94 function onMessage(message) { 95 function handleMessage(message) { 96 if (message.op === 'publish') { - 97 ros.emit(message.topic, message.msg); + 97 that.emit(message.topic, message.msg); 98 } else if (message.op === 'service_response') { - 99 ros.emit(message.id, message.values); + 99 that.emit(message.id, message.values); 100 } 101 }; 102 @@ -122,20 +122,20 @@ 115 * 116 * @param url - WebSocket URL for Rosbridge 117 */ -118 ros.connect = function(url) { -119 ros.socket = new WebSocket(url); -120 ros.socket.onopen = onOpen; -121 ros.socket.onclose = onClose; -122 ros.socket.onerror = onError; -123 ros.socket.onmessage = onMessage; +118 this.connect = function(url) { +119 that.socket = new WebSocket(url); +120 that.socket.onopen = onOpen; +121 that.socket.onclose = onClose; +122 that.socket.onerror = onError; +123 that.socket.onmessage = onMessage; 124 }; 125 126 /** 127 * Disconnect from the WebSocket server. 128 */ -129 ros.close = function() { -130 if (ros.socket) { -131 ros.socket.close(); +129 this.close = function() { +130 if (that.socket) { +131 that.socket.close(); 132 } 133 }; 134 @@ -150,7 +150,7 @@ 143 * @param level - User level as a string given by the client. 144 * @param end - End time of the client's session. 145 */ -146 ros.authenticate = function(mac, client, dest, rand, t, level, end) { +146 this.authenticate = function(mac, client, dest, rand, t, level, end) { 147 // create the request 148 var auth = { 149 op : 'auth', @@ -169,15 +169,15 @@ 162 /** 163 * Sends the message over the WebSocket, but queues the message up if not yet connected. 164 */ -165 ros.callOnConnection = function(message) { +165 this.callOnConnection = function(message) { 166 var messageJson = JSON.stringify(message); 167 -168 if (ros.socket.readyState !== WebSocket.OPEN) { -169 ros.once('connection', function() { -170 ros.socket.send(messageJson); +168 if (that.socket.readyState !== WebSocket.OPEN) { +169 that.once('connection', function() { +170 that.socket.send(messageJson); 171 }); 172 } else { -173 ros.socket.send(messageJson); +173 that.socket.send(messageJson); 174 } 175 }; 176 @@ -187,7 +187,7 @@ 180 * @param callback function with params: 181 * * topics - Array of topic names 182 */ -183 ros.getTopics = function(callback) { +183 this.getTopics = function(callback) { 184 var topicsClient = new ROSLIB.Service({ 185 name : '/rosapi/topics', 186 serviceType : 'rosapi/Topics' @@ -206,7 +206,7 @@ 199 * @param callback - function with the following params: 200 * * services - array of service names 201 */ -202 ros.getServices = function(callback) { +202 this.getServices = function(callback) { 203 var servicesClient = new ROSLIB.Service({ 204 name : '/rosapi/services', 205 serviceType : 'rosapi/Services' @@ -225,7 +225,7 @@ 218 * @param callback function with params: 219 * * params - array of param names. 220 */ -221 ros.getParams = function(callback) { +221 this.getParams = function(callback) { 222 var paramsClient = new ROSLIB.Service({ 223 name : '/rosapi/get_param_names', 224 serviceType : 'rosapi/GetParamNames' @@ -239,7 +239,7 @@ 232 233 // begin by checking if a URL was given 234 if (url) { -235 ros.connect(url); +235 this.connect(url); 236 } 237 }; 238 ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html index b111245dd..48a7bb1c8 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html @@ -19,11 +19,11 @@ 12 * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' 13 */ 14 ROSLIB.Service = function(options) { - 15 var service = this; + 15 var that = this; 16 options = options || {}; - 17 service.ros = options.ros; - 18 service.name = options.name; - 19 service.serviceType = options.serviceType; + 17 this.ros = options.ros; + 18 this.name = options.name; + 19 this.serviceType = options.serviceType; 20 21 /** 22 * Calls the service. Returns the service response in the callback. @@ -32,11 +32,11 @@ 25 * @param callback - function with params: 26 * * response - the response from the service request 27 */ - 28 service.callService = function(request, callback) { - 29 ros.idCounter++; - 30 serviceCallId = 'call_service:' + service.name + ':' + ros.idCounter; + 28 this.callService = function(request, callback) { + 29 that.ros.idCounter++; + 30 serviceCallId = 'call_service:' + that.name + ':' + that.ros.idCounter; 31 - 32 ros.once(serviceCallId, function(data) { + 32 that.ros.once(serviceCallId, function(data) { 33 var response = new ROSLIB.ServiceResponse(data); 34 callback(response); 35 }); @@ -49,10 +49,10 @@ 42 var call = { 43 op : 'call_service', 44 id : serviceCallId, - 45 service : service.name, + 45 service : that.name, 46 args : requestValues 47 }; - 48 ros.callOnConnection(call); + 48 that.ros.callOnConnection(call); 49 }; 50 }; 51 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html index 47caa9742..f21169b20 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html @@ -16,10 +16,10 @@ 9 * @param values - object matching the values of the request part from the .srv file. 10 */ 11 ROSLIB.ServiceRequest = function(values) { - 12 var serviceRequest = this; + 12 var that = this; 13 if (values) { 14 Object.keys(values).forEach(function(name) { - 15 serviceRequest[name] = values[name]; + 15 that[name] = values[name]; 16 }); 17 } 18 }; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html index 9db966a3f..0dff1bed1 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html @@ -16,10 +16,10 @@ 9 * @param values - object matching the values of the response part from the .srv file. 10 */ 11 ROSLIB.ServiceResponse = function(values) { - 12 var serviceResponse = this; + 12 var that = this; 13 if (values) { 14 Object.keys(values).forEach(function(name) { - 15 serviceResponse[name] = values[name]; + 15 that[name] = values[name]; 16 }); 17 } 18 }; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html index a2210fdf3..0ebab169a 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html @@ -25,25 +25,25 @@ 18 * * throttle_rate - the rate at which to throttle the topics 19 */ 20 ROSLIB.Topic = function(options) { - 21 var topic = this; + 21 var that = this; 22 options = options || {}; - 23 topic.ros = options.ros; - 24 topic.name = options.name; - 25 topic.messageType = options.messageType; - 26 topic.isAdvertised = false; - 27 topic.compression = options.compression || 'none'; - 28 topic.throttle_rate = options.throttle_rate || 0; + 23 this.ros = options.ros; + 24 this.name = options.name; + 25 this.messageType = options.messageType; + 26 this.isAdvertised = false; + 27 this.compression = options.compression || 'none'; + 28 this.throttle_rate = options.throttle_rate || 0; 29 30 // Check for valid compression types - 31 if (topic.compression && topic.compression !== 'png' && topic.compression !== 'none') { - 32 topic.emit('warning', topic.compression + 31 if (this.compression && this.compression !== 'png' && this.compression !== 'none') { + 32 this.emit('warning', this.compression 33 + ' compression is not supported. No comression will be used.'); 34 } 35 36 // Check if throttle rate is negative - 37 if (topic.throttle_rate < 0) { - 38 topic.emit('warning', topic.throttle_rate + ' is not allowed. Set to 0'); - 39 topic.throttle_rate = 0; + 37 if (this.throttle_rate < 0) { + 38 this.emit('warning', this.throttle_rate + ' is not allowed. Set to 0'); + 39 this.throttle_rate = 0; 40 } 41 42 /** @@ -53,75 +53,75 @@ 46 * @param callback - function with the following params: 47 * * message - the published message 48 */ - 49 topic.subscribe = function(callback) { - 50 topic.on('message', function(message) { + 49 this.subscribe = function(callback) { + 50 that.on('message', function(message) { 51 callback(message); 52 }); 53 - 54 ros.on(topic.name, function(data) { + 54 that.ros.on(that.name, function(data) { 55 var message = new ROSLIB.Message(data); - 56 topic.emit('message', message); + 56 that.emit('message', message); 57 }); 58 - 59 ros.idCounter++; - 60 var subscribeId = 'subscribe:' + topic.name + ':' + ros.idCounter; + 59 that.ros.idCounter++; + 60 var subscribeId = 'subscribe:' + that.name + ':' + that.ros.idCounter; 61 var call = { 62 op : 'subscribe', 63 id : subscribeId, - 64 type : topic.messageType, - 65 topic : topic.name, - 66 compression : topic.compression, - 67 throttle_rate : topic.throttle_rate + 64 type : that.messageType, + 65 topic : that.name, + 66 compression : that.compression, + 67 throttle_rate : that.throttle_rate 68 }; 69 - 70 ros.callOnConnection(call); + 70 that.ros.callOnConnection(call); 71 }; 72 73 /** 74 * Unregisters as a subscriber for the topic. Unsubscribing will remove 75 * all subscribe callbacks. 76 */ - 77 topic.unsubscribe = function() { - 78 ros.removeAllListeners([ topic.name ]); - 79 ros.idCounter++; - 80 var unsubscribeId = 'unsubscribe:' + topic.name + ':' + ros.idCounter; + 77 this.unsubscribe = function() { + 78 that.ros.removeAllListeners([ that.name ]); + 79 that.ros.idCounter++; + 80 var unsubscribeId = 'unsubscribe:' + that.name + ':' + that.ros.idCounter; 81 var call = { 82 op : 'unsubscribe', 83 id : unsubscribeId, - 84 topic : topic.name + 84 topic : that.name 85 }; - 86 ros.callOnConnection(call); + 86 that.ros.callOnConnection(call); 87 }; 88 89 /** 90 * Registers as a publisher for the topic. 91 */ - 92 topic.advertise = function() { - 93 ros.idCounter++; - 94 var advertiseId = 'advertise:' + topic.name + ':' + ros.idCounter; + 92 this.advertise = function() { + 93 that.ros.idCounter++; + 94 var advertiseId = 'advertise:' + that.name + ':' + that.ros.idCounter; 95 var call = { 96 op : 'advertise', 97 id : advertiseId, - 98 type : topic.messageType, - 99 topic : topic.name + 98 type : that.messageType, + 99 topic : that.name 100 }; -101 ros.callOnConnection(call); -102 topic.isAdvertised = true; +101 that.ros.callOnConnection(call); +102 that.isAdvertised = true; 103 }; 104 105 /** 106 * Unregisters as a publisher for the topic. 107 */ -108 topic.unadvertise = function() { -109 ros.idCounter++; -110 var unadvertiseId = 'unadvertise:' + topic.name + ':' + ros.idCounter; +108 this.unadvertise = function() { +109 that.ros.idCounter++; +110 var unadvertiseId = 'unadvertise:' + that.name + ':' + that.ros.idCounter; 111 var call = { 112 op : 'unadvertise', 113 id : unadvertiseId, -114 topic : topic.name +114 topic : that.name 115 }; -116 ros.callOnConnection(call); -117 topic.isAdvertised = false; +116 that.ros.callOnConnection(call); +117 that.isAdvertised = false; 118 }; 119 120 /** @@ -129,20 +129,20 @@ 122 * 123 * @param message - A ROSLIB.Message object. 124 */ -125 topic.publish = function(message) { -126 if (!topic.isAdvertised) { -127 topic.advertise(); +125 this.publish = function(message) { +126 if (!that.isAdvertised) { +127 that.advertise(); 128 } 129 -130 ros.idCounter++; -131 var publishId = 'publish:' + topic.name + ':' + ros.idCounter; +130 that.ros.idCounter++; +131 var publishId = 'publish:' + that.name + ':' + that.ros.idCounter; 132 var call = { 133 op : 'publish', 134 id : publishId, -135 topic : topic.name, +135 topic : that.name, 136 msg : message 137 }; -138 ros.callOnConnection(call); +138 that.ros.callOnConnection(call); 139 }; 140 }; 141 ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; diff --git a/examples/simple.html b/examples/simple.html index fdaadb0e3..1f29cd95f 100644 --- a/examples/simple.html +++ b/examples/simple.html @@ -131,7 +131,7 @@

    Simple roslib Example

    console for the output.

    1. roscore
    2. -
    3. rostopic pub /listener std_msgs/String "Hello, World!"
    4. +
    5. rostopic pub /listener std_msgs/String "Hello, World"
    6. rostopic echo /cmd_vel
    7. rosrun rospy_tutorials add_two_ints_server
    8. roslaunch rosbridge_server rosbridge_websocket.launch
    9. diff --git a/src/core/Message.js b/src/core/Message.js index bad20908a..b372770e5 100644 --- a/src/core/Message.js +++ b/src/core/Message.js @@ -9,10 +9,10 @@ * @param values - object matching the fields defined in the .msg definition file. */ ROSLIB.Message = function(values) { - var message = this; + var that = this; if (values) { Object.keys(values).forEach(function(name) { - message[name] = values[name]; + that[name] = values[name]; }); } }; diff --git a/src/core/Param.js b/src/core/Param.js index 249702f9a..65d8cef8d 100644 --- a/src/core/Param.js +++ b/src/core/Param.js @@ -10,9 +10,9 @@ * * name - the param name, like max_vel_x */ ROSLIB.Param = function(options) { - var param = this; + var that = this; options = options || {}; - param.name = options.name; + this.name = options.name; /** * Fetches the value of the param. @@ -20,14 +20,14 @@ ROSLIB.Param = function(options) { * @param callback - function with the following params: * * value - the value of the param from ROS. */ - param.get = function(callback) { + this.get = function(callback) { var paramClient = new ROSLIB.Service({ name : '/rosapi/get_param', serviceType : 'rosapi/GetParam' }); var request = new ROSLIB.ServiceRequest({ - name : param.name, + name : that.name, value : JSON.stringify('') }); @@ -42,14 +42,14 @@ ROSLIB.Param = function(options) { * * @param value - value to set param to. */ - param.set = function(value) { + this.set = function(value) { var paramClient = new ROSLIB.Service({ name : '/rosapi/set_param', serviceType : 'rosapi/SetParam' }); var request = new ROSLIB.ServiceRequest({ - name : param.name, + name : that.name, value : JSON.stringify(value) }); diff --git a/src/core/Ros.js b/src/core/Ros.js index d5d1e7048..1daf91af3 100644 --- a/src/core/Ros.js +++ b/src/core/Ros.js @@ -16,8 +16,8 @@ * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. */ ROSLIB.Ros = function(url) { - var ros = this; - ros.socket = null; + var that = this; + this.socket = null; /** * Emits a 'connection' event on WebSocket connection. @@ -25,7 +25,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onOpen(event) { - ros.emit('connection', event); + that.emit('connection', event); }; /** @@ -34,7 +34,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onClose(event) { - ros.emit('close', event); + that.emit('close', event); }; /** @@ -43,7 +43,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onError(event) { - ros.emit('error', event); + that.emit('error', event); }; /** @@ -94,9 +94,9 @@ ROSLIB.Ros = function(url) { function onMessage(message) { function handleMessage(message) { if (message.op === 'publish') { - ros.emit(message.topic, message.msg); + that.emit(message.topic, message.msg); } else if (message.op === 'service_response') { - ros.emit(message.id, message.values); + that.emit(message.id, message.values); } }; @@ -115,20 +115,20 @@ ROSLIB.Ros = function(url) { * * @param url - WebSocket URL for Rosbridge */ - ros.connect = function(url) { - ros.socket = new WebSocket(url); - ros.socket.onopen = onOpen; - ros.socket.onclose = onClose; - ros.socket.onerror = onError; - ros.socket.onmessage = onMessage; + this.connect = function(url) { + that.socket = new WebSocket(url); + that.socket.onopen = onOpen; + that.socket.onclose = onClose; + that.socket.onerror = onError; + that.socket.onmessage = onMessage; }; /** * Disconnect from the WebSocket server. */ - ros.close = function() { - if (ros.socket) { - ros.socket.close(); + this.close = function() { + if (that.socket) { + that.socket.close(); } }; @@ -143,7 +143,7 @@ ROSLIB.Ros = function(url) { * @param level - User level as a string given by the client. * @param end - End time of the client's session. */ - ros.authenticate = function(mac, client, dest, rand, t, level, end) { + this.authenticate = function(mac, client, dest, rand, t, level, end) { // create the request var auth = { op : 'auth', @@ -162,15 +162,15 @@ ROSLIB.Ros = function(url) { /** * Sends the message over the WebSocket, but queues the message up if not yet connected. */ - ros.callOnConnection = function(message) { + this.callOnConnection = function(message) { var messageJson = JSON.stringify(message); - if (ros.socket.readyState !== WebSocket.OPEN) { - ros.once('connection', function() { - ros.socket.send(messageJson); + if (that.socket.readyState !== WebSocket.OPEN) { + that.once('connection', function() { + that.socket.send(messageJson); }); } else { - ros.socket.send(messageJson); + that.socket.send(messageJson); } }; @@ -180,7 +180,7 @@ ROSLIB.Ros = function(url) { * @param callback function with params: * * topics - Array of topic names */ - ros.getTopics = function(callback) { + this.getTopics = function(callback) { var topicsClient = new ROSLIB.Service({ name : '/rosapi/topics', serviceType : 'rosapi/Topics' @@ -199,7 +199,7 @@ ROSLIB.Ros = function(url) { * @param callback - function with the following params: * * services - array of service names */ - ros.getServices = function(callback) { + this.getServices = function(callback) { var servicesClient = new ROSLIB.Service({ name : '/rosapi/services', serviceType : 'rosapi/Services' @@ -218,7 +218,7 @@ ROSLIB.Ros = function(url) { * @param callback function with params: * * params - array of param names. */ - ros.getParams = function(callback) { + this.getParams = function(callback) { var paramsClient = new ROSLIB.Service({ name : '/rosapi/get_param_names', serviceType : 'rosapi/GetParamNames' @@ -232,7 +232,7 @@ ROSLIB.Ros = function(url) { // begin by checking if a URL was given if (url) { - ros.connect(url); + this.connect(url); } }; ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; diff --git a/src/core/Service.js b/src/core/Service.js index 77ab5aceb..ffd806274 100644 --- a/src/core/Service.js +++ b/src/core/Service.js @@ -12,11 +12,11 @@ * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' */ ROSLIB.Service = function(options) { - var service = this; + var that = this; options = options || {}; - service.ros = options.ros; - service.name = options.name; - service.serviceType = options.serviceType; + this.ros = options.ros; + this.name = options.name; + this.serviceType = options.serviceType; /** * Calls the service. Returns the service response in the callback. @@ -25,11 +25,11 @@ ROSLIB.Service = function(options) { * @param callback - function with params: * * response - the response from the service request */ - service.callService = function(request, callback) { - ros.idCounter++; - serviceCallId = 'call_service:' + service.name + ':' + ros.idCounter; + this.callService = function(request, callback) { + that.ros.idCounter++; + serviceCallId = 'call_service:' + that.name + ':' + that.ros.idCounter; - ros.once(serviceCallId, function(data) { + that.ros.once(serviceCallId, function(data) { var response = new ROSLIB.ServiceResponse(data); callback(response); }); @@ -42,9 +42,9 @@ ROSLIB.Service = function(options) { var call = { op : 'call_service', id : serviceCallId, - service : service.name, + service : that.name, args : requestValues }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; }; diff --git a/src/core/ServiceRequest.js b/src/core/ServiceRequest.js index 505200c44..7a6fe52fb 100644 --- a/src/core/ServiceRequest.js +++ b/src/core/ServiceRequest.js @@ -9,10 +9,10 @@ * @param values - object matching the values of the request part from the .srv file. */ ROSLIB.ServiceRequest = function(values) { - var serviceRequest = this; + var that = this; if (values) { Object.keys(values).forEach(function(name) { - serviceRequest[name] = values[name]; + that[name] = values[name]; }); } }; diff --git a/src/core/ServiceResponse.js b/src/core/ServiceResponse.js index 8e612f474..c577ed4cd 100644 --- a/src/core/ServiceResponse.js +++ b/src/core/ServiceResponse.js @@ -9,10 +9,10 @@ * @param values - object matching the values of the response part from the .srv file. */ ROSLIB.ServiceResponse = function(values) { - var serviceResponse = this; + var that = this; if (values) { Object.keys(values).forEach(function(name) { - serviceResponse[name] = values[name]; + that[name] = values[name]; }); } }; diff --git a/src/core/Topic.js b/src/core/Topic.js index fec19a2fd..4dd70af07 100644 --- a/src/core/Topic.js +++ b/src/core/Topic.js @@ -18,25 +18,25 @@ * * throttle_rate - the rate at which to throttle the topics */ ROSLIB.Topic = function(options) { - var topic = this; + var that = this; options = options || {}; - topic.ros = options.ros; - topic.name = options.name; - topic.messageType = options.messageType; - topic.isAdvertised = false; - topic.compression = options.compression || 'none'; - topic.throttle_rate = options.throttle_rate || 0; + this.ros = options.ros; + this.name = options.name; + this.messageType = options.messageType; + this.isAdvertised = false; + this.compression = options.compression || 'none'; + this.throttle_rate = options.throttle_rate || 0; // Check for valid compression types - if (topic.compression && topic.compression !== 'png' && topic.compression !== 'none') { - topic.emit('warning', topic.compression + if (this.compression && this.compression !== 'png' && this.compression !== 'none') { + this.emit('warning', this.compression + ' compression is not supported. No comression will be used.'); } // Check if throttle rate is negative - if (topic.throttle_rate < 0) { - topic.emit('warning', topic.throttle_rate + ' is not allowed. Set to 0'); - topic.throttle_rate = 0; + if (this.throttle_rate < 0) { + this.emit('warning', this.throttle_rate + ' is not allowed. Set to 0'); + this.throttle_rate = 0; } /** @@ -46,75 +46,75 @@ ROSLIB.Topic = function(options) { * @param callback - function with the following params: * * message - the published message */ - topic.subscribe = function(callback) { - topic.on('message', function(message) { + this.subscribe = function(callback) { + that.on('message', function(message) { callback(message); }); - ros.on(topic.name, function(data) { + that.ros.on(that.name, function(data) { var message = new ROSLIB.Message(data); - topic.emit('message', message); + that.emit('message', message); }); - ros.idCounter++; - var subscribeId = 'subscribe:' + topic.name + ':' + ros.idCounter; + that.ros.idCounter++; + var subscribeId = 'subscribe:' + that.name + ':' + that.ros.idCounter; var call = { op : 'subscribe', id : subscribeId, - type : topic.messageType, - topic : topic.name, - compression : topic.compression, - throttle_rate : topic.throttle_rate + type : that.messageType, + topic : that.name, + compression : that.compression, + throttle_rate : that.throttle_rate }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; /** * Unregisters as a subscriber for the topic. Unsubscribing will remove * all subscribe callbacks. */ - topic.unsubscribe = function() { - ros.removeAllListeners([ topic.name ]); - ros.idCounter++; - var unsubscribeId = 'unsubscribe:' + topic.name + ':' + ros.idCounter; + this.unsubscribe = function() { + that.ros.removeAllListeners([ that.name ]); + that.ros.idCounter++; + var unsubscribeId = 'unsubscribe:' + that.name + ':' + that.ros.idCounter; var call = { op : 'unsubscribe', id : unsubscribeId, - topic : topic.name + topic : that.name }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; /** * Registers as a publisher for the topic. */ - topic.advertise = function() { - ros.idCounter++; - var advertiseId = 'advertise:' + topic.name + ':' + ros.idCounter; + this.advertise = function() { + that.ros.idCounter++; + var advertiseId = 'advertise:' + that.name + ':' + that.ros.idCounter; var call = { op : 'advertise', id : advertiseId, - type : topic.messageType, - topic : topic.name + type : that.messageType, + topic : that.name }; - ros.callOnConnection(call); - topic.isAdvertised = true; + that.ros.callOnConnection(call); + that.isAdvertised = true; }; /** * Unregisters as a publisher for the topic. */ - topic.unadvertise = function() { - ros.idCounter++; - var unadvertiseId = 'unadvertise:' + topic.name + ':' + ros.idCounter; + this.unadvertise = function() { + that.ros.idCounter++; + var unadvertiseId = 'unadvertise:' + that.name + ':' + that.ros.idCounter; var call = { op : 'unadvertise', id : unadvertiseId, - topic : topic.name + topic : that.name }; - ros.callOnConnection(call); - topic.isAdvertised = false; + that.ros.callOnConnection(call); + that.isAdvertised = false; }; /** @@ -122,20 +122,20 @@ ROSLIB.Topic = function(options) { * * @param message - A ROSLIB.Message object. */ - topic.publish = function(message) { - if (!topic.isAdvertised) { - topic.advertise(); + this.publish = function(message) { + if (!that.isAdvertised) { + that.advertise(); } - ros.idCounter++; - var publishId = 'publish:' + topic.name + ':' + ros.idCounter; + that.ros.idCounter++; + var publishId = 'publish:' + that.name + ':' + that.ros.idCounter; var call = { op : 'publish', id : publishId, - topic : topic.name, + topic : that.name, msg : message }; - ros.callOnConnection(call); + that.ros.callOnConnection(call); }; }; ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; From 6ac48ac78a177c829992ba97dd9fff8e3d48039a Mon Sep 17 00:00:00 2001 From: Russell Toris Date: Fri, 15 Mar 2013 14:58:11 -0700 Subject: [PATCH 3/3] that changed to more meaningful name --- build/roslib.js | 161 +++++++++--------- build/roslib.min.js | 2 +- doc/files.html | 2 +- doc/index.html | 2 +- doc/symbols/ROSLIB.ActionClient.html | 2 +- doc/symbols/ROSLIB.Goal.html | 6 +- doc/symbols/ROSLIB.Message.html | 2 +- doc/symbols/ROSLIB.Param.html | 3 +- doc/symbols/ROSLIB.Ros.html | 2 +- doc/symbols/ROSLIB.Service.html | 2 +- doc/symbols/ROSLIB.ServiceRequest.html | 2 +- doc/symbols/ROSLIB.ServiceResponse.html | 2 +- doc/symbols/ROSLIB.Topic.html | 2 +- doc/symbols/_global_.html | 2 +- ...oslibjs_src_actionlib_ActionClient.js.html | 10 +- ...vy_src_roslibjs_src_actionlib_Goal.js.html | 14 +- ...oovy_src_roslibjs_src_core_Message.js.html | 4 +- ...groovy_src_roslibjs_src_core_Param.js.html | 106 ++++++------ ...S_groovy_src_roslibjs_src_core_Ros.js.html | 145 ++++++++-------- ...oovy_src_roslibjs_src_core_Service.js.html | 12 +- ...c_roslibjs_src_core_ServiceRequest.js.html | 4 +- ..._roslibjs_src_core_ServiceResponse.js.html | 4 +- ...groovy_src_roslibjs_src_core_Topic.js.html | 66 +++---- examples/simple.html | 2 + src/actionlib/ActionClient.js | 10 +- src/actionlib/Goal.js | 14 +- src/core/Message.js | 4 +- src/core/Param.js | 10 +- src/core/Ros.js | 37 ++-- src/core/Service.js | 12 +- src/core/ServiceRequest.js | 4 +- src/core/ServiceResponse.js | 4 +- src/core/Topic.js | 66 +++---- 33 files changed, 372 insertions(+), 348 deletions(-) diff --git a/build/roslib.js b/build/roslib.js index 864e570c9..bee4e2932 100644 --- a/build/roslib.js +++ b/build/roslib.js @@ -26,7 +26,7 @@ var ROSLIB = ROSLIB || { * * timeout - the timeout length when connecting to the action server */ ROSLIB.ActionClient = function(options) { - var that = this; + var actionClient = this; options = options || {}; this.ros = options.ros; this.serverName = options.serverName; @@ -80,7 +80,7 @@ ROSLIB.ActionClient = function(options) { statusListener.subscribe(function(statusMessage) { receivedStatus = true; statusMessage.status_list.forEach(function(status) { - var goal = that.goals[status.goal_id.id]; + var goal = actionClient.goals[status.goal_id.id]; if (goal) { goal.emit('status', status); } @@ -89,7 +89,7 @@ ROSLIB.ActionClient = function(options) { // subscribe the the feedback topic feedbackListener.subscribe(function(feedbackMessage) { - var goal = that.goals[feedbackMessage.status.goal_id.id]; + var goal = actionClient.goals[feedbackMessage.status.goal_id.id]; if (goal) { goal.emit('status', feedbackMessage.status); goal.emit('feedback', feedbackMessage.feedback); @@ -98,7 +98,7 @@ ROSLIB.ActionClient = function(options) { // subscribe to the result topic resultListener.subscribe(function(resultMessage) { - var goal = that.goals[resultMessage.status.goal_id.id]; + var goal = actionClient.goals[resultMessage.status.goal_id.id]; if (goal) { goal.emit('status', resultMessage.status); @@ -110,7 +110,7 @@ ROSLIB.ActionClient = function(options) { if (this.timeout) { setTimeout(function() { if (!receivedStatus) { - that.emit('timeout'); + actionClient.emit('timeout'); } }, this.timeout); } @@ -121,7 +121,7 @@ ROSLIB.ActionClient.prototype.__proto__ = EventEmitter2.prototype; */ /** - * An actionlib goal that is associated with an action server. + * An actionlib goal goal is associated with an action server. * * Emits the following events: * * 'timeout' - if a timeout occurred while sending a goal @@ -133,7 +133,7 @@ ROSLIB.ActionClient.prototype.__proto__ = EventEmitter2.prototype; */ ROSLIB.Goal = function(options) { - var that = this; + var goal = this; this.actionClient = options.actionClient; this.goalMessage = options.goalMessage; this.isFinished = false; @@ -147,11 +147,11 @@ ROSLIB.Goal = function(options) { * @param timeout (optional) - a timeout length for the goal's result */ this.send = function(timeout) { - that.actionClient.goalTopic.publish(that.goalMessage); + goal.actionClient.goalTopic.publish(goal.goalMessage); if (timeout) { setTimeout(function() { - if (!that.isFinished) { - that.emit('timeout'); + if (!goal.isFinished) { + goal.emit('timeout'); } }, timeout); } @@ -162,9 +162,9 @@ ROSLIB.Goal = function(options) { */ this.cancel = function() { var cancelMessage = new ROSLIB.Message({ - id : that.goalID + id : goal.goalID }); - that.actionClient.cancelTopic.publish(cancelMessage); + goal.actionClient.cancelTopic.publish(cancelMessage); }; // create a random ID @@ -210,10 +210,10 @@ ROSLIB.Goal.prototype.__proto__ = EventEmitter2.prototype; * @param values - object matching the fields defined in the .msg definition file. */ ROSLIB.Message = function(values) { - var that = this; + var message = this; if (values) { Object.keys(values).forEach(function(name) { - that[name] = values[name]; + message[name] = values[name]; }); } }; @@ -226,11 +226,13 @@ ROSLIB.Message = function(values) { * * @constructor * @param options - possible keys include: + * * ros - the ROSLIB.Ros connection handle * * name - the param name, like max_vel_x */ ROSLIB.Param = function(options) { - var that = this; + var param = this; options = options || {}; + this.ros = options.ros; this.name = options.name; /** @@ -241,12 +243,13 @@ ROSLIB.Param = function(options) { */ this.get = function(callback) { var paramClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/get_param', serviceType : 'rosapi/GetParam' }); var request = new ROSLIB.ServiceRequest({ - name : that.name, + name : param.name, value : JSON.stringify('') }); @@ -263,12 +266,13 @@ ROSLIB.Param = function(options) { */ this.set = function(value) { var paramClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/set_param', serviceType : 'rosapi/SetParam' }); var request = new ROSLIB.ServiceRequest({ - name : that.name, + name : param.name, value : JSON.stringify(value) }); @@ -294,7 +298,7 @@ ROSLIB.Param = function(options) { * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. */ ROSLIB.Ros = function(url) { - var that = this; + var ros = this; this.socket = null; /** @@ -303,7 +307,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onOpen(event) { - that.emit('connection', event); + ros.emit('connection', event); }; /** @@ -312,7 +316,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onClose(event) { - that.emit('close', event); + ros.emit('close', event); }; /** @@ -321,7 +325,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onError(event) { - that.emit('error', event); + ros.emit('error', event); }; /** @@ -372,9 +376,9 @@ ROSLIB.Ros = function(url) { function onMessage(message) { function handleMessage(message) { if (message.op === 'publish') { - that.emit(message.topic, message.msg); + ros.emit(message.topic, message.msg); } else if (message.op === 'service_response') { - that.emit(message.id, message.values); + ros.emit(message.id, message.values); } }; @@ -394,19 +398,19 @@ ROSLIB.Ros = function(url) { * @param url - WebSocket URL for Rosbridge */ this.connect = function(url) { - that.socket = new WebSocket(url); - that.socket.onopen = onOpen; - that.socket.onclose = onClose; - that.socket.onerror = onError; - that.socket.onmessage = onMessage; + ros.socket = new WebSocket(url); + ros.socket.onopen = onOpen; + ros.socket.onclose = onClose; + ros.socket.onerror = onError; + ros.socket.onmessage = onMessage; }; /** * Disconnect from the WebSocket server. */ this.close = function() { - if (that.socket) { - that.socket.close(); + if (ros.socket) { + ros.socket.close(); } }; @@ -443,12 +447,12 @@ ROSLIB.Ros = function(url) { this.callOnConnection = function(message) { var messageJson = JSON.stringify(message); - if (that.socket.readyState !== WebSocket.OPEN) { - that.once('connection', function() { - that.socket.send(messageJson); + if (ros.socket.readyState !== WebSocket.OPEN) { + ros.once('connection', function() { + ros.socket.send(messageJson); }); } else { - that.socket.send(messageJson); + ros.socket.send(messageJson); } }; @@ -460,6 +464,7 @@ ROSLIB.Ros = function(url) { */ this.getTopics = function(callback) { var topicsClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/topics', serviceType : 'rosapi/Topics' }); @@ -479,6 +484,7 @@ ROSLIB.Ros = function(url) { */ this.getServices = function(callback) { var servicesClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/services', serviceType : 'rosapi/Services' }); @@ -498,6 +504,7 @@ ROSLIB.Ros = function(url) { */ this.getParams = function(callback) { var paramsClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/get_param_names', serviceType : 'rosapi/GetParamNames' }); @@ -528,7 +535,7 @@ ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' */ ROSLIB.Service = function(options) { - var that = this; + var service = this; options = options || {}; this.ros = options.ros; this.name = options.name; @@ -542,10 +549,10 @@ ROSLIB.Service = function(options) { * * response - the response from the service request */ this.callService = function(request, callback) { - that.ros.idCounter++; - serviceCallId = 'call_service:' + that.name + ':' + that.ros.idCounter; + service.ros.idCounter++; + serviceCallId = 'call_service:' + service.name + ':' + service.ros.idCounter; - that.ros.once(serviceCallId, function(data) { + service.ros.once(serviceCallId, function(data) { var response = new ROSLIB.ServiceResponse(data); callback(response); }); @@ -558,10 +565,10 @@ ROSLIB.Service = function(options) { var call = { op : 'call_service', id : serviceCallId, - service : that.name, + service : service.name, args : requestValues }; - that.ros.callOnConnection(call); + service.ros.callOnConnection(call); }; }; /** @@ -575,10 +582,10 @@ ROSLIB.Service = function(options) { * @param values - object matching the values of the request part from the .srv file. */ ROSLIB.ServiceRequest = function(values) { - var that = this; + var serviceRequest = this; if (values) { Object.keys(values).forEach(function(name) { - that[name] = values[name]; + serviceRequest[name] = values[name]; }); } }; @@ -593,10 +600,10 @@ ROSLIB.ServiceRequest = function(values) { * @param values - object matching the values of the response part from the .srv file. */ ROSLIB.ServiceResponse = function(values) { - var that = this; + var serviceResponse = this; if (values) { Object.keys(values).forEach(function(name) { - that[name] = values[name]; + serviceResponse[name] = values[name]; }); } }; @@ -620,7 +627,7 @@ ROSLIB.ServiceResponse = function(values) { * * throttle_rate - the rate at which to throttle the topics */ ROSLIB.Topic = function(options) { - var that = this; + var topic = this; options = options || {}; this.ros = options.ros; this.name = options.name; @@ -649,27 +656,27 @@ ROSLIB.Topic = function(options) { * * message - the published message */ this.subscribe = function(callback) { - that.on('message', function(message) { + topic.on('message', function(message) { callback(message); }); - that.ros.on(that.name, function(data) { + topic.ros.on(topic.name, function(data) { var message = new ROSLIB.Message(data); - that.emit('message', message); + topic.emit('message', message); }); - that.ros.idCounter++; - var subscribeId = 'subscribe:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var subscribeId = 'subscribe:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'subscribe', id : subscribeId, - type : that.messageType, - topic : that.name, - compression : that.compression, - throttle_rate : that.throttle_rate + type : topic.messageType, + topic : topic.name, + compression : topic.compression, + throttle_rate : topic.throttle_rate }; - that.ros.callOnConnection(call); + topic.ros.callOnConnection(call); }; /** @@ -677,46 +684,46 @@ ROSLIB.Topic = function(options) { * all subscribe callbacks. */ this.unsubscribe = function() { - that.ros.removeAllListeners([ that.name ]); - that.ros.idCounter++; - var unsubscribeId = 'unsubscribe:' + that.name + ':' + that.ros.idCounter; + topic.ros.removeAllListeners([ topic.name ]); + topic.ros.idCounter++; + var unsubscribeId = 'unsubscribe:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'unsubscribe', id : unsubscribeId, - topic : that.name + topic : topic.name }; - that.ros.callOnConnection(call); + topic.ros.callOnConnection(call); }; /** * Registers as a publisher for the topic. */ this.advertise = function() { - that.ros.idCounter++; - var advertiseId = 'advertise:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var advertiseId = 'advertise:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'advertise', id : advertiseId, - type : that.messageType, - topic : that.name + type : topic.messageType, + topic : topic.name }; - that.ros.callOnConnection(call); - that.isAdvertised = true; + topic.ros.callOnConnection(call); + topic.isAdvertised = true; }; /** * Unregisters as a publisher for the topic. */ this.unadvertise = function() { - that.ros.idCounter++; - var unadvertiseId = 'unadvertise:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var unadvertiseId = 'unadvertise:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'unadvertise', id : unadvertiseId, - topic : that.name + topic : topic.name }; - that.ros.callOnConnection(call); - that.isAdvertised = false; + topic.ros.callOnConnection(call); + topic.isAdvertised = false; }; /** @@ -725,19 +732,19 @@ ROSLIB.Topic = function(options) { * @param message - A ROSLIB.Message object. */ this.publish = function(message) { - if (!that.isAdvertised) { - that.advertise(); + if (!topic.isAdvertised) { + topic.advertise(); } - that.ros.idCounter++; - var publishId = 'publish:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var publishId = 'publish:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'publish', id : publishId, - topic : that.name, + topic : topic.name, msg : message }; - that.ros.callOnConnection(call); + topic.ros.callOnConnection(call); }; }; ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; diff --git a/build/roslib.min.js b/build/roslib.min.js index cbbb6cdde..d7fbdc29f 100644 --- a/build/roslib.min.js +++ b/build/roslib.min.js @@ -1 +1 @@ -var ROSLIB=ROSLIB||{REVISION:"1"};ROSLIB.ActionClient=function(b){var c=this;b=b||{};this.ros=b.ros;this.serverName=b.serverName;this.actionName=b.actionName;this.timeout=b.timeout;this.goals={};var a=false;var d=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/feedback",messageType:this.actionName+"Feedback"});var e=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/status",messageType:"actionlib_msgs/GoalStatusArray"});var f=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/result",messageType:this.actionName+"Result"});this.goalTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/goal",messageType:this.actionName+"Goal"});this.cancelTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/cancel",messageType:"actionlib_msgs/GoalID"});this.cancel=function(){var g=new ROSLIB.Message({});this.cancelTopic.publish(g)};this.goalTopic.advertise();this.cancelTopic.advertise();e.subscribe(function(g){a=true;g.status_list.forEach(function(h){var i=c.goals[h.goal_id.id];if(i){i.emit("status",h)}})});d.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("feedback",h.feedback)}});f.subscribe(function(h){var g=c.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("result",h.result)}});if(this.timeout){setTimeout(function(){if(!a){c.emit("timeout")}},this.timeout)}};ROSLIB.ActionClient.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Goal=function(b){var c=this;this.actionClient=b.actionClient;this.goalMessage=b.goalMessage;this.isFinished=false;var a=new Date();this.send=function(d){c.actionClient.goalTopic.publish(c.goalMessage);if(d){setTimeout(function(){if(!c.isFinished){c.emit("timeout")}},d)}};this.cancel=function(){var d=new ROSLIB.Message({id:c.goalID});c.actionClient.cancelTopic.publish(d)};this.goalID="goal_"+Math.random()+"_"+a.getTime();this.goalMessage=new ROSLIB.Message({goal_id:{stamp:{secs:0,nsecs:0},id:this.goalID},goal:this.goalMessage});this.on("status",function(d){this.status=d});this.on("result",function(d){this.isFinished=true;this.result=d});this.on("feedback",function(d){this.feedback=d});this.actionClient.goals[this.goalID]=this};ROSLIB.Goal.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Message=function(a){var b=this;if(a){Object.keys(a).forEach(function(c){b[c]=a[c]})}};ROSLIB.Param=function(a){var b=this;a=a||{};this.name=a.name;this.get=function(e){var d=new ROSLIB.Service({name:"/rosapi/get_param",serviceType:"rosapi/GetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify("")});d.callService(c,function(f){var g=JSON.parse(f.value);e(g)})};this.set=function(e){var d=new ROSLIB.Service({name:"/rosapi/set_param",serviceType:"rosapi/SetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify(e)});d.callService(c,function(){})}};ROSLIB.Ros=function(c){var e=this;this.socket=null;function b(h){e.emit("connection",h)}function a(h){e.emit("close",h)}function d(h){e.emit("error",h)}function g(h,j){var i=new Image();i.onload=function(){var k=document.createElement("canvas");var m=k.getContext("2d");k.width=i.width;k.height=i.height;m.drawImage(i,0,0);var p=m.getImageData(0,0,i.width,i.height).data;var n="";for(var l=0;l=0){j.cbs.splice(h,1);if(j.cbs.length==0){delete this.frame_infos[i]}this.needUpdate=true}}};var f=d.Pose=function(h,i){this.position=new a;this.orientation=new e;if(h!==undefined){this.position.copy(h)}if(i!==undefined){this.orientation.copy(i)}};f.prototype={constructor:f,copy:function(h){this.position.copy(h.position);this.orientation.copy(h.orientation)}};var c=d.Transform=function(i,h){this.translation=new a;this.rotation=new e;if(i!==undefined){this.translation.copy(i)}if(h!==undefined){this.rotation.copy(h)}};c.prototype={constructor:c,apply:function(h){this.rotation.multiplyVec3(h.position);h.position.add(h.position,this.translation);h.orientation.multiply(this.rotation,h.orientation);return h},applyInverse:function(i){var h=this.rotation.clone().inverse();h.multiplyVec3(i.position);i.position.sub(i.position,this.translation);i.orientation.multiply(h,i.orientation);return i},copy:function(h){this.translation.copy(h.translation);this.rotation.copy(h.rotation)}};var e=d.Quaternion=function(h,k,j,i){this.x=h||0;this.y=k||0;this.z=j||0;this.w=(i!==undefined)?i:1};e.prototype={constructor:e,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;this.w=h.w;return this},inverse:function(){this.conjugate().normalize();return this},conjugate:function(){this.x*=-1;this.y*=-1;this.z*=-1;return this},normalize:function(){var h=Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w);if(h===0){this.x=0;this.y=0;this.z=0;this.w=1}else{h=1/h;this.x=this.x*h;this.y=this.y*h;this.z=this.z*h;this.w=this.w*h}return this},multiply:function(q,p){var n=q.x,m=q.y,l=q.z,o=q.w,j=p.x,i=p.y,h=p.z,k=p.w;this.x=n*k+m*h-l*i+o*j;this.y=-n*h+m*k+l*j+o*i;this.z=n*i-m*j+l*k+o*h;this.w=-n*j-m*i-l*h+o*k;return this},multiplyVec3:function(j,t){if(!t){t=j}var s=j.x,r=j.y,q=j.z,o=this.x,n=this.y,m=this.z,p=this.w;var k=p*s+n*q-m*r,i=p*r+m*s-o*q,h=p*q+o*r-n*s,l=-o*s-n*r-m*q;t.x=k*p+l*-o+i*-m-h*-n;t.y=i*p+l*-n+h*-o-k*-m;t.z=h*p+l*-m+k*-n-i*-o;return t},clone:function(){return new e(this.x,this.y,this.z,this.w)}};var a=d.Vector3=function(h,j,i){this.x=h||0;this.y=j||0;this.z=i||0};a.prototype={constructor:a,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;return this},add:function(i,h){this.x=i.x+h.x;this.y=i.y+h.y;this.z=i.z+h.z;return this},sub:function(i,h){this.x=i.x-h.x;this.y=i.y-h.y;this.z=i.z-h.z;return this},clone:function(){return new a(this.x,this.y,this.z)}};return d})); \ No newline at end of file +var ROSLIB=ROSLIB||{REVISION:"1"};ROSLIB.ActionClient=function(b){var d=this;b=b||{};this.ros=b.ros;this.serverName=b.serverName;this.actionName=b.actionName;this.timeout=b.timeout;this.goals={};var a=false;var c=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/feedback",messageType:this.actionName+"Feedback"});var e=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/status",messageType:"actionlib_msgs/GoalStatusArray"});var f=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/result",messageType:this.actionName+"Result"});this.goalTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/goal",messageType:this.actionName+"Goal"});this.cancelTopic=new ROSLIB.Topic({ros:this.ros,name:this.serverName+"/cancel",messageType:"actionlib_msgs/GoalID"});this.cancel=function(){var g=new ROSLIB.Message({});this.cancelTopic.publish(g)};this.goalTopic.advertise();this.cancelTopic.advertise();e.subscribe(function(g){a=true;g.status_list.forEach(function(h){var i=d.goals[h.goal_id.id];if(i){i.emit("status",h)}})});c.subscribe(function(h){var g=d.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("feedback",h.feedback)}});f.subscribe(function(h){var g=d.goals[h.status.goal_id.id];if(g){g.emit("status",h.status);g.emit("result",h.result)}});if(this.timeout){setTimeout(function(){if(!a){d.emit("timeout")}},this.timeout)}};ROSLIB.ActionClient.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Goal=function(c){var b=this;this.actionClient=c.actionClient;this.goalMessage=c.goalMessage;this.isFinished=false;var a=new Date();this.send=function(d){b.actionClient.goalTopic.publish(b.goalMessage);if(d){setTimeout(function(){if(!b.isFinished){b.emit("timeout")}},d)}};this.cancel=function(){var d=new ROSLIB.Message({id:b.goalID});b.actionClient.cancelTopic.publish(d)};this.goalID="goal_"+Math.random()+"_"+a.getTime();this.goalMessage=new ROSLIB.Message({goal_id:{stamp:{secs:0,nsecs:0},id:this.goalID},goal:this.goalMessage});this.on("status",function(d){this.status=d});this.on("result",function(d){this.isFinished=true;this.result=d});this.on("feedback",function(d){this.feedback=d});this.actionClient.goals[this.goalID]=this};ROSLIB.Goal.prototype.__proto__=EventEmitter2.prototype;ROSLIB.Message=function(a){var b=this;if(a){Object.keys(a).forEach(function(c){b[c]=a[c]})}};ROSLIB.Param=function(a){var b=this;a=a||{};this.ros=a.ros;this.name=a.name;this.get=function(e){var d=new ROSLIB.Service({ros:ros,name:"/rosapi/get_param",serviceType:"rosapi/GetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify("")});d.callService(c,function(f){var g=JSON.parse(f.value);e(g)})};this.set=function(e){var d=new ROSLIB.Service({ros:ros,name:"/rosapi/set_param",serviceType:"rosapi/SetParam"});var c=new ROSLIB.ServiceRequest({name:b.name,value:JSON.stringify(e)});d.callService(c,function(){})}};ROSLIB.Ros=function(d){var c=this;this.socket=null;function b(h){c.emit("connection",h)}function a(h){c.emit("close",h)}function e(h){c.emit("error",h)}function g(h,j){var i=new Image();i.onload=function(){var k=document.createElement("canvas");var m=k.getContext("2d");k.width=i.width;k.height=i.height;m.drawImage(i,0,0);var p=m.getImageData(0,0,i.width,i.height).data;var n="";for(var l=0;l=0){j.cbs.splice(h,1);if(j.cbs.length==0){delete this.frame_infos[i]}this.needUpdate=true}}};var f=d.Pose=function(h,i){this.position=new a;this.orientation=new e;if(h!==undefined){this.position.copy(h)}if(i!==undefined){this.orientation.copy(i)}};f.prototype={constructor:f,copy:function(h){this.position.copy(h.position);this.orientation.copy(h.orientation)}};var c=d.Transform=function(i,h){this.translation=new a;this.rotation=new e;if(i!==undefined){this.translation.copy(i)}if(h!==undefined){this.rotation.copy(h)}};c.prototype={constructor:c,apply:function(h){this.rotation.multiplyVec3(h.position);h.position.add(h.position,this.translation);h.orientation.multiply(this.rotation,h.orientation);return h},applyInverse:function(i){var h=this.rotation.clone().inverse();h.multiplyVec3(i.position);i.position.sub(i.position,this.translation);i.orientation.multiply(h,i.orientation);return i},copy:function(h){this.translation.copy(h.translation);this.rotation.copy(h.rotation)}};var e=d.Quaternion=function(h,k,j,i){this.x=h||0;this.y=k||0;this.z=j||0;this.w=(i!==undefined)?i:1};e.prototype={constructor:e,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;this.w=h.w;return this},inverse:function(){this.conjugate().normalize();return this},conjugate:function(){this.x*=-1;this.y*=-1;this.z*=-1;return this},normalize:function(){var h=Math.sqrt(this.x*this.x+this.y*this.y+this.z*this.z+this.w*this.w);if(h===0){this.x=0;this.y=0;this.z=0;this.w=1}else{h=1/h;this.x=this.x*h;this.y=this.y*h;this.z=this.z*h;this.w=this.w*h}return this},multiply:function(q,p){var n=q.x,m=q.y,l=q.z,o=q.w,j=p.x,i=p.y,h=p.z,k=p.w;this.x=n*k+m*h-l*i+o*j;this.y=-n*h+m*k+l*j+o*i;this.z=n*i-m*j+l*k+o*h;this.w=-n*j-m*i-l*h+o*k;return this},multiplyVec3:function(j,t){if(!t){t=j}var s=j.x,r=j.y,q=j.z,o=this.x,n=this.y,m=this.z,p=this.w;var k=p*s+n*q-m*r,i=p*r+m*s-o*q,h=p*q+o*r-n*s,l=-o*s-n*r-m*q;t.x=k*p+l*-o+i*-m-h*-n;t.y=i*p+l*-n+h*-o-k*-m;t.z=h*p+l*-m+k*-n-i*-o;return t},clone:function(){return new e(this.x,this.y,this.z,this.w)}};var a=d.Vector3=function(h,j,i){this.x=h||0;this.y=j||0;this.z=i||0};a.prototype={constructor:a,copy:function(h){this.x=h.x;this.y=h.y;this.z=h.z;return this},add:function(i,h){this.x=i.x+h.x;this.y=i.y+h.y;this.z=i.z+h.z;return this},sub:function(i,h){this.x=i.x-h.x;this.y=i.y-h.y;this.z=i.z-h.z;return this},clone:function(){return new a(this.x,this.y,this.z)}};return d})); \ No newline at end of file diff --git a/doc/files.html b/doc/files.html index 95532d3b9..dacb071df 100644 --- a/doc/files.html +++ b/doc/files.html @@ -348,7 +348,7 @@

      - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)

    \ No newline at end of file diff --git a/doc/index.html b/doc/index.html index 59dc2c561..b3da1e78f 100644 --- a/doc/index.html +++ b/doc/index.html @@ -276,7 +276,7 @@

    ROSLIB.Topic

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    \ No newline at end of file diff --git a/doc/symbols/ROSLIB.ActionClient.html b/doc/symbols/ROSLIB.ActionClient.html index 2fde3538f..11e006566 100644 --- a/doc/symbols/ROSLIB.ActionClient.html +++ b/doc/symbols/ROSLIB.ActionClient.html @@ -389,7 +389,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Goal.html b/doc/symbols/ROSLIB.Goal.html index b724b979b..cf0cf156b 100644 --- a/doc/symbols/ROSLIB.Goal.html +++ b/doc/symbols/ROSLIB.Goal.html @@ -250,7 +250,7 @@

    ROSLIB.Goal(object)
    -
    An actionlib goal that is associated with an action server.
    +
    An actionlib goal goal is associated with an action server.
    @@ -313,7 +313,7 @@

    - An actionlib goal that is associated with an action server. + An actionlib goal goal is associated with an action server. Emits the following events: * 'timeout' - if a timeout occurred while sending a goal @@ -429,7 +429,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Message.html b/doc/symbols/ROSLIB.Message.html index f807e5cf4..e7cdaf075 100644 --- a/doc/symbols/ROSLIB.Message.html +++ b/doc/symbols/ROSLIB.Message.html @@ -322,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Param.html b/doc/symbols/ROSLIB.Param.html index 6545d5681..83fff972e 100644 --- a/doc/symbols/ROSLIB.Param.html +++ b/doc/symbols/ROSLIB.Param.html @@ -329,6 +329,7 @@

    - possible keys include: + * ros - the ROSLIB.Ros connection handle * name - the param name, like max_vel_x
    @@ -437,7 +438,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Ros.html b/doc/symbols/ROSLIB.Ros.html index 3b9cc6bb0..e11997331 100644 --- a/doc/symbols/ROSLIB.Ros.html +++ b/doc/symbols/ROSLIB.Ros.html @@ -931,7 +931,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Service.html b/doc/symbols/ROSLIB.Service.html index 0454e0573..50e104aff 100644 --- a/doc/symbols/ROSLIB.Service.html +++ b/doc/symbols/ROSLIB.Service.html @@ -397,7 +397,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.ServiceRequest.html b/doc/symbols/ROSLIB.ServiceRequest.html index cec4de281..bdca0f796 100644 --- a/doc/symbols/ROSLIB.ServiceRequest.html +++ b/doc/symbols/ROSLIB.ServiceRequest.html @@ -322,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.ServiceResponse.html b/doc/symbols/ROSLIB.ServiceResponse.html index 9be064e43..36243f65b 100644 --- a/doc/symbols/ROSLIB.ServiceResponse.html +++ b/doc/symbols/ROSLIB.ServiceResponse.html @@ -322,7 +322,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/ROSLIB.Topic.html b/doc/symbols/ROSLIB.Topic.html index 17c2157a8..a321fb01a 100644 --- a/doc/symbols/ROSLIB.Topic.html +++ b/doc/symbols/ROSLIB.Topic.html @@ -550,7 +550,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/_global_.html b/doc/symbols/_global_.html index 4679fcd4d..fdab0c9e5 100644 --- a/doc/symbols/_global_.html +++ b/doc/symbols/_global_.html @@ -319,7 +319,7 @@

    - Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:44:04 GMT-0700 (PDT) + Documentation generated by JsDoc Toolkit 2.4.0 on Fri Mar 15 2013 14:57:47 GMT-0700 (PDT)
    diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html index 8ce886c40..b187db792 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_ActionClient.js.html @@ -26,7 +26,7 @@ 19 * * timeout - the timeout length when connecting to the action server 20 */ 21 ROSLIB.ActionClient = function(options) { - 22 var that = this; + 22 var actionClient = this; 23 options = options || {}; 24 this.ros = options.ros; 25 this.serverName = options.serverName; @@ -80,7 +80,7 @@ 73 statusListener.subscribe(function(statusMessage) { 74 receivedStatus = true; 75 statusMessage.status_list.forEach(function(status) { - 76 var goal = that.goals[status.goal_id.id]; + 76 var goal = actionClient.goals[status.goal_id.id]; 77 if (goal) { 78 goal.emit('status', status); 79 } @@ -89,7 +89,7 @@ 82 83 // subscribe the the feedback topic 84 feedbackListener.subscribe(function(feedbackMessage) { - 85 var goal = that.goals[feedbackMessage.status.goal_id.id]; + 85 var goal = actionClient.goals[feedbackMessage.status.goal_id.id]; 86 if (goal) { 87 goal.emit('status', feedbackMessage.status); 88 goal.emit('feedback', feedbackMessage.feedback); @@ -98,7 +98,7 @@ 91 92 // subscribe to the result topic 93 resultListener.subscribe(function(resultMessage) { - 94 var goal = that.goals[resultMessage.status.goal_id.id]; + 94 var goal = actionClient.goals[resultMessage.status.goal_id.id]; 95 96 if (goal) { 97 goal.emit('status', resultMessage.status); @@ -110,7 +110,7 @@ 103 if (this.timeout) { 104 setTimeout(function() { 105 if (!receivedStatus) { -106 that.emit('timeout'); +106 actionClient.emit('timeout'); 107 } 108 }, this.timeout); 109 } diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html index 529d07cb9..663f90478 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_actionlib_Goal.js.html @@ -10,7 +10,7 @@ 3 */ 4 5 /** - 6 * An actionlib goal that is associated with an action server. + 6 * An actionlib goal goal is associated with an action server. 7 * 8 * Emits the following events: 9 * * 'timeout' - if a timeout occurred while sending a goal @@ -22,7 +22,7 @@ 15 */ 16 17 ROSLIB.Goal = function(options) { - 18 var that = this; + 18 var goal = this; 19 this.actionClient = options.actionClient; 20 this.goalMessage = options.goalMessage; 21 this.isFinished = false; @@ -36,11 +36,11 @@ 29 * @param timeout (optional) - a timeout length for the goal's result 30 */ 31 this.send = function(timeout) { - 32 that.actionClient.goalTopic.publish(that.goalMessage); + 32 goal.actionClient.goalTopic.publish(goal.goalMessage); 33 if (timeout) { 34 setTimeout(function() { - 35 if (!that.isFinished) { - 36 that.emit('timeout'); + 35 if (!goal.isFinished) { + 36 goal.emit('timeout'); 37 } 38 }, timeout); 39 } @@ -51,9 +51,9 @@ 44 */ 45 this.cancel = function() { 46 var cancelMessage = new ROSLIB.Message({ - 47 id : that.goalID + 47 id : goal.goalID 48 }); - 49 that.actionClient.cancelTopic.publish(cancelMessage); + 49 goal.actionClient.cancelTopic.publish(cancelMessage); 50 }; 51 52 // create a random ID diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html index 62faddd27..b238319ea 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Message.js.html @@ -16,10 +16,10 @@ 9 * @param values - object matching the fields defined in the .msg definition file. 10 */ 11 ROSLIB.Message = function(values) { - 12 var that = this; + 12 var message = this; 13 if (values) { 14 Object.keys(values).forEach(function(name) { - 15 that[name] = values[name]; + 15 message[name] = values[name]; 16 }); 17 } 18 }; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html index be5fe0691..ea156e022 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Param.js.html @@ -14,54 +14,58 @@ 7 * 8 * @constructor 9 * @param options - possible keys include: - 10 * * name - the param name, like max_vel_x - 11 */ - 12 ROSLIB.Param = function(options) { - 13 var that = this; - 14 options = options || {}; - 15 this.name = options.name; - 16 - 17 /** - 18 * Fetches the value of the param. - 19 * - 20 * @param callback - function with the following params: - 21 * * value - the value of the param from ROS. - 22 */ - 23 this.get = function(callback) { - 24 var paramClient = new ROSLIB.Service({ - 25 name : '/rosapi/get_param', - 26 serviceType : 'rosapi/GetParam' - 27 }); - 28 - 29 var request = new ROSLIB.ServiceRequest({ - 30 name : that.name, - 31 value : JSON.stringify('') - 32 }); - 33 - 34 paramClient.callService(request, function(result) { - 35 var value = JSON.parse(result.value); - 36 callback(value); - 37 }); - 38 }; - 39 - 40 /** - 41 * Sets the value of the param in ROS. - 42 * - 43 * @param value - value to set param to. - 44 */ - 45 this.set = function(value) { - 46 var paramClient = new ROSLIB.Service({ - 47 name : '/rosapi/set_param', - 48 serviceType : 'rosapi/SetParam' - 49 }); - 50 - 51 var request = new ROSLIB.ServiceRequest({ - 52 name : that.name, - 53 value : JSON.stringify(value) - 54 }); - 55 - 56 paramClient.callService(request, function() { - 57 }); - 58 }; - 59 }; - 60 \ No newline at end of file + 10 * * ros - the ROSLIB.Ros connection handle + 11 * * name - the param name, like max_vel_x + 12 */ + 13 ROSLIB.Param = function(options) { + 14 var param = this; + 15 options = options || {}; + 16 this.ros = options.ros; + 17 this.name = options.name; + 18 + 19 /** + 20 * Fetches the value of the param. + 21 * + 22 * @param callback - function with the following params: + 23 * * value - the value of the param from ROS. + 24 */ + 25 this.get = function(callback) { + 26 var paramClient = new ROSLIB.Service({ + 27 ros : ros, + 28 name : '/rosapi/get_param', + 29 serviceType : 'rosapi/GetParam' + 30 }); + 31 + 32 var request = new ROSLIB.ServiceRequest({ + 33 name : param.name, + 34 value : JSON.stringify('') + 35 }); + 36 + 37 paramClient.callService(request, function(result) { + 38 var value = JSON.parse(result.value); + 39 callback(value); + 40 }); + 41 }; + 42 + 43 /** + 44 * Sets the value of the param in ROS. + 45 * + 46 * @param value - value to set param to. + 47 */ + 48 this.set = function(value) { + 49 var paramClient = new ROSLIB.Service({ + 50 ros : ros, + 51 name : '/rosapi/set_param', + 52 serviceType : 'rosapi/SetParam' + 53 }); + 54 + 55 var request = new ROSLIB.ServiceRequest({ + 56 name : param.name, + 57 value : JSON.stringify(value) + 58 }); + 59 + 60 paramClient.callService(request, function() { + 61 }); + 62 }; + 63 }; + 64 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html index 8a42f63fb..2fc7e766d 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Ros.js.html @@ -23,7 +23,7 @@ 16 * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. 17 */ 18 ROSLIB.Ros = function(url) { - 19 var that = this; + 19 var ros = this; 20 this.socket = null; 21 22 /** @@ -32,7 +32,7 @@ 25 * @param event - the argument to emit with the event. 26 */ 27 function onOpen(event) { - 28 that.emit('connection', event); + 28 ros.emit('connection', event); 29 }; 30 31 /** @@ -41,7 +41,7 @@ 34 * @param event - the argument to emit with the event. 35 */ 36 function onClose(event) { - 37 that.emit('close', event); + 37 ros.emit('close', event); 38 }; 39 40 /** @@ -50,7 +50,7 @@ 43 * @param event - the argument to emit with the event. 44 */ 45 function onError(event) { - 46 that.emit('error', event); + 46 ros.emit('error', event); 47 }; 48 49 /** @@ -101,9 +101,9 @@ 94 function onMessage(message) { 95 function handleMessage(message) { 96 if (message.op === 'publish') { - 97 that.emit(message.topic, message.msg); + 97 ros.emit(message.topic, message.msg); 98 } else if (message.op === 'service_response') { - 99 that.emit(message.id, message.values); + 99 ros.emit(message.id, message.values); 100 } 101 }; 102 @@ -123,19 +123,19 @@ 116 * @param url - WebSocket URL for Rosbridge 117 */ 118 this.connect = function(url) { -119 that.socket = new WebSocket(url); -120 that.socket.onopen = onOpen; -121 that.socket.onclose = onClose; -122 that.socket.onerror = onError; -123 that.socket.onmessage = onMessage; +119 ros.socket = new WebSocket(url); +120 ros.socket.onopen = onOpen; +121 ros.socket.onclose = onClose; +122 ros.socket.onerror = onError; +123 ros.socket.onmessage = onMessage; 124 }; 125 126 /** 127 * Disconnect from the WebSocket server. 128 */ 129 this.close = function() { -130 if (that.socket) { -131 that.socket.close(); +130 if (ros.socket) { +131 ros.socket.close(); 132 } 133 }; 134 @@ -172,12 +172,12 @@ 165 this.callOnConnection = function(message) { 166 var messageJson = JSON.stringify(message); 167 -168 if (that.socket.readyState !== WebSocket.OPEN) { -169 that.once('connection', function() { -170 that.socket.send(messageJson); +168 if (ros.socket.readyState !== WebSocket.OPEN) { +169 ros.once('connection', function() { +170 ros.socket.send(messageJson); 171 }); 172 } else { -173 that.socket.send(messageJson); +173 ros.socket.send(messageJson); 174 } 175 }; 176 @@ -189,58 +189,61 @@ 182 */ 183 this.getTopics = function(callback) { 184 var topicsClient = new ROSLIB.Service({ -185 name : '/rosapi/topics', -186 serviceType : 'rosapi/Topics' -187 }); -188 -189 var request = new ROSLIB.ServiceRequest(); -190 -191 topicsClient.callService(request, function(result) { -192 callback(result.topics); -193 }); -194 }; -195 -196 /** -197 * Retrieves list of active service names in ROS. -198 * -199 * @param callback - function with the following params: -200 * * services - array of service names -201 */ -202 this.getServices = function(callback) { -203 var servicesClient = new ROSLIB.Service({ -204 name : '/rosapi/services', -205 serviceType : 'rosapi/Services' -206 }); -207 -208 var request = new ROSLIB.ServiceRequest(); +185 ros : ros, +186 name : '/rosapi/topics', +187 serviceType : 'rosapi/Topics' +188 }); +189 +190 var request = new ROSLIB.ServiceRequest(); +191 +192 topicsClient.callService(request, function(result) { +193 callback(result.topics); +194 }); +195 }; +196 +197 /** +198 * Retrieves list of active service names in ROS. +199 * +200 * @param callback - function with the following params: +201 * * services - array of service names +202 */ +203 this.getServices = function(callback) { +204 var servicesClient = new ROSLIB.Service({ +205 ros : ros, +206 name : '/rosapi/services', +207 serviceType : 'rosapi/Services' +208 }); 209 -210 servicesClient.callService(request, function(result) { -211 callback(result.services); -212 }); -213 }; -214 -215 /** -216 * Retrieves list of param names from the ROS Parameter Server. -217 * -218 * @param callback function with params: -219 * * params - array of param names. -220 */ -221 this.getParams = function(callback) { -222 var paramsClient = new ROSLIB.Service({ -223 name : '/rosapi/get_param_names', -224 serviceType : 'rosapi/GetParamNames' -225 }); -226 -227 var request = new ROSLIB.ServiceRequest(); -228 paramsClient.callService(request, function(result) { -229 callback(result.names); -230 }); -231 }; -232 -233 // begin by checking if a URL was given -234 if (url) { -235 this.connect(url); -236 } -237 }; -238 ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; -239 \ No newline at end of file +210 var request = new ROSLIB.ServiceRequest(); +211 +212 servicesClient.callService(request, function(result) { +213 callback(result.services); +214 }); +215 }; +216 +217 /** +218 * Retrieves list of param names from the ROS Parameter Server. +219 * +220 * @param callback function with params: +221 * * params - array of param names. +222 */ +223 this.getParams = function(callback) { +224 var paramsClient = new ROSLIB.Service({ +225 ros : ros, +226 name : '/rosapi/get_param_names', +227 serviceType : 'rosapi/GetParamNames' +228 }); +229 +230 var request = new ROSLIB.ServiceRequest(); +231 paramsClient.callService(request, function(result) { +232 callback(result.names); +233 }); +234 }; +235 +236 // begin by checking if a URL was given +237 if (url) { +238 this.connect(url); +239 } +240 }; +241 ROSLIB.Ros.prototype.__proto__ = EventEmitter2.prototype; +242 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html index 48a7bb1c8..db03f4fa6 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Service.js.html @@ -19,7 +19,7 @@ 12 * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' 13 */ 14 ROSLIB.Service = function(options) { - 15 var that = this; + 15 var service = this; 16 options = options || {}; 17 this.ros = options.ros; 18 this.name = options.name; @@ -33,10 +33,10 @@ 26 * * response - the response from the service request 27 */ 28 this.callService = function(request, callback) { - 29 that.ros.idCounter++; - 30 serviceCallId = 'call_service:' + that.name + ':' + that.ros.idCounter; + 29 service.ros.idCounter++; + 30 serviceCallId = 'call_service:' + service.name + ':' + service.ros.idCounter; 31 - 32 that.ros.once(serviceCallId, function(data) { + 32 service.ros.once(serviceCallId, function(data) { 33 var response = new ROSLIB.ServiceResponse(data); 34 callback(response); 35 }); @@ -49,10 +49,10 @@ 42 var call = { 43 op : 'call_service', 44 id : serviceCallId, - 45 service : that.name, + 45 service : service.name, 46 args : requestValues 47 }; - 48 that.ros.callOnConnection(call); + 48 service.ros.callOnConnection(call); 49 }; 50 }; 51 \ No newline at end of file diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html index f21169b20..47caa9742 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceRequest.js.html @@ -16,10 +16,10 @@ 9 * @param values - object matching the values of the request part from the .srv file. 10 */ 11 ROSLIB.ServiceRequest = function(values) { - 12 var that = this; + 12 var serviceRequest = this; 13 if (values) { 14 Object.keys(values).forEach(function(name) { - 15 that[name] = values[name]; + 15 serviceRequest[name] = values[name]; 16 }); 17 } 18 }; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html index 0dff1bed1..9db966a3f 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_ServiceResponse.js.html @@ -16,10 +16,10 @@ 9 * @param values - object matching the values of the response part from the .srv file. 10 */ 11 ROSLIB.ServiceResponse = function(values) { - 12 var that = this; + 12 var serviceResponse = this; 13 if (values) { 14 Object.keys(values).forEach(function(name) { - 15 that[name] = values[name]; + 15 serviceResponse[name] = values[name]; 16 }); 17 } 18 }; diff --git a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html index 0ebab169a..ca2a028a8 100644 --- a/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html +++ b/doc/symbols/src/_home_tor1pal_Documents_WPI_RAIL_ROS_groovy_src_roslibjs_src_core_Topic.js.html @@ -25,7 +25,7 @@ 18 * * throttle_rate - the rate at which to throttle the topics 19 */ 20 ROSLIB.Topic = function(options) { - 21 var that = this; + 21 var topic = this; 22 options = options || {}; 23 this.ros = options.ros; 24 this.name = options.name; @@ -54,27 +54,27 @@ 47 * * message - the published message 48 */ 49 this.subscribe = function(callback) { - 50 that.on('message', function(message) { + 50 topic.on('message', function(message) { 51 callback(message); 52 }); 53 - 54 that.ros.on(that.name, function(data) { + 54 topic.ros.on(topic.name, function(data) { 55 var message = new ROSLIB.Message(data); - 56 that.emit('message', message); + 56 topic.emit('message', message); 57 }); 58 - 59 that.ros.idCounter++; - 60 var subscribeId = 'subscribe:' + that.name + ':' + that.ros.idCounter; + 59 topic.ros.idCounter++; + 60 var subscribeId = 'subscribe:' + topic.name + ':' + topic.ros.idCounter; 61 var call = { 62 op : 'subscribe', 63 id : subscribeId, - 64 type : that.messageType, - 65 topic : that.name, - 66 compression : that.compression, - 67 throttle_rate : that.throttle_rate + 64 type : topic.messageType, + 65 topic : topic.name, + 66 compression : topic.compression, + 67 throttle_rate : topic.throttle_rate 68 }; 69 - 70 that.ros.callOnConnection(call); + 70 topic.ros.callOnConnection(call); 71 }; 72 73 /** @@ -82,46 +82,46 @@ 75 * all subscribe callbacks. 76 */ 77 this.unsubscribe = function() { - 78 that.ros.removeAllListeners([ that.name ]); - 79 that.ros.idCounter++; - 80 var unsubscribeId = 'unsubscribe:' + that.name + ':' + that.ros.idCounter; + 78 topic.ros.removeAllListeners([ topic.name ]); + 79 topic.ros.idCounter++; + 80 var unsubscribeId = 'unsubscribe:' + topic.name + ':' + topic.ros.idCounter; 81 var call = { 82 op : 'unsubscribe', 83 id : unsubscribeId, - 84 topic : that.name + 84 topic : topic.name 85 }; - 86 that.ros.callOnConnection(call); + 86 topic.ros.callOnConnection(call); 87 }; 88 89 /** 90 * Registers as a publisher for the topic. 91 */ 92 this.advertise = function() { - 93 that.ros.idCounter++; - 94 var advertiseId = 'advertise:' + that.name + ':' + that.ros.idCounter; + 93 topic.ros.idCounter++; + 94 var advertiseId = 'advertise:' + topic.name + ':' + topic.ros.idCounter; 95 var call = { 96 op : 'advertise', 97 id : advertiseId, - 98 type : that.messageType, - 99 topic : that.name + 98 type : topic.messageType, + 99 topic : topic.name 100 }; -101 that.ros.callOnConnection(call); -102 that.isAdvertised = true; +101 topic.ros.callOnConnection(call); +102 topic.isAdvertised = true; 103 }; 104 105 /** 106 * Unregisters as a publisher for the topic. 107 */ 108 this.unadvertise = function() { -109 that.ros.idCounter++; -110 var unadvertiseId = 'unadvertise:' + that.name + ':' + that.ros.idCounter; +109 topic.ros.idCounter++; +110 var unadvertiseId = 'unadvertise:' + topic.name + ':' + topic.ros.idCounter; 111 var call = { 112 op : 'unadvertise', 113 id : unadvertiseId, -114 topic : that.name +114 topic : topic.name 115 }; -116 that.ros.callOnConnection(call); -117 that.isAdvertised = false; +116 topic.ros.callOnConnection(call); +117 topic.isAdvertised = false; 118 }; 119 120 /** @@ -130,19 +130,19 @@ 123 * @param message - A ROSLIB.Message object. 124 */ 125 this.publish = function(message) { -126 if (!that.isAdvertised) { -127 that.advertise(); +126 if (!topic.isAdvertised) { +127 topic.advertise(); 128 } 129 -130 that.ros.idCounter++; -131 var publishId = 'publish:' + that.name + ':' + that.ros.idCounter; +130 topic.ros.idCounter++; +131 var publishId = 'publish:' + topic.name + ':' + topic.ros.idCounter; 132 var call = { 133 op : 'publish', 134 id : publishId, -135 topic : that.name, +135 topic : topic.name, 136 msg : message 137 }; -138 that.ros.callOnConnection(call); +138 topic.ros.callOnConnection(call); 139 }; 140 }; 141 ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype; diff --git a/examples/simple.html b/examples/simple.html index 1f29cd95f..aeb40fc50 100644 --- a/examples/simple.html +++ b/examples/simple.html @@ -102,6 +102,7 @@ // First, we create a Param object with the name of the param. var maxVelX = new ROSLIB.Param({ + ros : ros, name : 'max_vel_y' }); @@ -115,6 +116,7 @@ // --------------------- var favoriteColor = new ROSLIB.Param({ + ros : ros, name : 'favorite_color' }); diff --git a/src/actionlib/ActionClient.js b/src/actionlib/ActionClient.js index cc7eec9ed..4d51ec3ff 100644 --- a/src/actionlib/ActionClient.js +++ b/src/actionlib/ActionClient.js @@ -19,7 +19,7 @@ * * timeout - the timeout length when connecting to the action server */ ROSLIB.ActionClient = function(options) { - var that = this; + var actionClient = this; options = options || {}; this.ros = options.ros; this.serverName = options.serverName; @@ -73,7 +73,7 @@ ROSLIB.ActionClient = function(options) { statusListener.subscribe(function(statusMessage) { receivedStatus = true; statusMessage.status_list.forEach(function(status) { - var goal = that.goals[status.goal_id.id]; + var goal = actionClient.goals[status.goal_id.id]; if (goal) { goal.emit('status', status); } @@ -82,7 +82,7 @@ ROSLIB.ActionClient = function(options) { // subscribe the the feedback topic feedbackListener.subscribe(function(feedbackMessage) { - var goal = that.goals[feedbackMessage.status.goal_id.id]; + var goal = actionClient.goals[feedbackMessage.status.goal_id.id]; if (goal) { goal.emit('status', feedbackMessage.status); goal.emit('feedback', feedbackMessage.feedback); @@ -91,7 +91,7 @@ ROSLIB.ActionClient = function(options) { // subscribe to the result topic resultListener.subscribe(function(resultMessage) { - var goal = that.goals[resultMessage.status.goal_id.id]; + var goal = actionClient.goals[resultMessage.status.goal_id.id]; if (goal) { goal.emit('status', resultMessage.status); @@ -103,7 +103,7 @@ ROSLIB.ActionClient = function(options) { if (this.timeout) { setTimeout(function() { if (!receivedStatus) { - that.emit('timeout'); + actionClient.emit('timeout'); } }, this.timeout); } diff --git a/src/actionlib/Goal.js b/src/actionlib/Goal.js index 696e2057b..0a0fb6a1e 100644 --- a/src/actionlib/Goal.js +++ b/src/actionlib/Goal.js @@ -3,7 +3,7 @@ */ /** - * An actionlib goal that is associated with an action server. + * An actionlib goal goal is associated with an action server. * * Emits the following events: * * 'timeout' - if a timeout occurred while sending a goal @@ -15,7 +15,7 @@ */ ROSLIB.Goal = function(options) { - var that = this; + var goal = this; this.actionClient = options.actionClient; this.goalMessage = options.goalMessage; this.isFinished = false; @@ -29,11 +29,11 @@ ROSLIB.Goal = function(options) { * @param timeout (optional) - a timeout length for the goal's result */ this.send = function(timeout) { - that.actionClient.goalTopic.publish(that.goalMessage); + goal.actionClient.goalTopic.publish(goal.goalMessage); if (timeout) { setTimeout(function() { - if (!that.isFinished) { - that.emit('timeout'); + if (!goal.isFinished) { + goal.emit('timeout'); } }, timeout); } @@ -44,9 +44,9 @@ ROSLIB.Goal = function(options) { */ this.cancel = function() { var cancelMessage = new ROSLIB.Message({ - id : that.goalID + id : goal.goalID }); - that.actionClient.cancelTopic.publish(cancelMessage); + goal.actionClient.cancelTopic.publish(cancelMessage); }; // create a random ID diff --git a/src/core/Message.js b/src/core/Message.js index b372770e5..bad20908a 100644 --- a/src/core/Message.js +++ b/src/core/Message.js @@ -9,10 +9,10 @@ * @param values - object matching the fields defined in the .msg definition file. */ ROSLIB.Message = function(values) { - var that = this; + var message = this; if (values) { Object.keys(values).forEach(function(name) { - that[name] = values[name]; + message[name] = values[name]; }); } }; diff --git a/src/core/Param.js b/src/core/Param.js index 65d8cef8d..b9af10341 100644 --- a/src/core/Param.js +++ b/src/core/Param.js @@ -7,11 +7,13 @@ * * @constructor * @param options - possible keys include: + * * ros - the ROSLIB.Ros connection handle * * name - the param name, like max_vel_x */ ROSLIB.Param = function(options) { - var that = this; + var param = this; options = options || {}; + this.ros = options.ros; this.name = options.name; /** @@ -22,12 +24,13 @@ ROSLIB.Param = function(options) { */ this.get = function(callback) { var paramClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/get_param', serviceType : 'rosapi/GetParam' }); var request = new ROSLIB.ServiceRequest({ - name : that.name, + name : param.name, value : JSON.stringify('') }); @@ -44,12 +47,13 @@ ROSLIB.Param = function(options) { */ this.set = function(value) { var paramClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/set_param', serviceType : 'rosapi/SetParam' }); var request = new ROSLIB.ServiceRequest({ - name : that.name, + name : param.name, value : JSON.stringify(value) }); diff --git a/src/core/Ros.js b/src/core/Ros.js index 1daf91af3..2dc20e148 100644 --- a/src/core/Ros.js +++ b/src/core/Ros.js @@ -16,7 +16,7 @@ * @param url (optional) - The WebSocket URL for rosbridge. Can be specified later with `connect`. */ ROSLIB.Ros = function(url) { - var that = this; + var ros = this; this.socket = null; /** @@ -25,7 +25,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onOpen(event) { - that.emit('connection', event); + ros.emit('connection', event); }; /** @@ -34,7 +34,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onClose(event) { - that.emit('close', event); + ros.emit('close', event); }; /** @@ -43,7 +43,7 @@ ROSLIB.Ros = function(url) { * @param event - the argument to emit with the event. */ function onError(event) { - that.emit('error', event); + ros.emit('error', event); }; /** @@ -94,9 +94,9 @@ ROSLIB.Ros = function(url) { function onMessage(message) { function handleMessage(message) { if (message.op === 'publish') { - that.emit(message.topic, message.msg); + ros.emit(message.topic, message.msg); } else if (message.op === 'service_response') { - that.emit(message.id, message.values); + ros.emit(message.id, message.values); } }; @@ -116,19 +116,19 @@ ROSLIB.Ros = function(url) { * @param url - WebSocket URL for Rosbridge */ this.connect = function(url) { - that.socket = new WebSocket(url); - that.socket.onopen = onOpen; - that.socket.onclose = onClose; - that.socket.onerror = onError; - that.socket.onmessage = onMessage; + ros.socket = new WebSocket(url); + ros.socket.onopen = onOpen; + ros.socket.onclose = onClose; + ros.socket.onerror = onError; + ros.socket.onmessage = onMessage; }; /** * Disconnect from the WebSocket server. */ this.close = function() { - if (that.socket) { - that.socket.close(); + if (ros.socket) { + ros.socket.close(); } }; @@ -165,12 +165,12 @@ ROSLIB.Ros = function(url) { this.callOnConnection = function(message) { var messageJson = JSON.stringify(message); - if (that.socket.readyState !== WebSocket.OPEN) { - that.once('connection', function() { - that.socket.send(messageJson); + if (ros.socket.readyState !== WebSocket.OPEN) { + ros.once('connection', function() { + ros.socket.send(messageJson); }); } else { - that.socket.send(messageJson); + ros.socket.send(messageJson); } }; @@ -182,6 +182,7 @@ ROSLIB.Ros = function(url) { */ this.getTopics = function(callback) { var topicsClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/topics', serviceType : 'rosapi/Topics' }); @@ -201,6 +202,7 @@ ROSLIB.Ros = function(url) { */ this.getServices = function(callback) { var servicesClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/services', serviceType : 'rosapi/Services' }); @@ -220,6 +222,7 @@ ROSLIB.Ros = function(url) { */ this.getParams = function(callback) { var paramsClient = new ROSLIB.Service({ + ros : ros, name : '/rosapi/get_param_names', serviceType : 'rosapi/GetParamNames' }); diff --git a/src/core/Service.js b/src/core/Service.js index ffd806274..9eaee213c 100644 --- a/src/core/Service.js +++ b/src/core/Service.js @@ -12,7 +12,7 @@ * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' */ ROSLIB.Service = function(options) { - var that = this; + var service = this; options = options || {}; this.ros = options.ros; this.name = options.name; @@ -26,10 +26,10 @@ ROSLIB.Service = function(options) { * * response - the response from the service request */ this.callService = function(request, callback) { - that.ros.idCounter++; - serviceCallId = 'call_service:' + that.name + ':' + that.ros.idCounter; + service.ros.idCounter++; + serviceCallId = 'call_service:' + service.name + ':' + service.ros.idCounter; - that.ros.once(serviceCallId, function(data) { + service.ros.once(serviceCallId, function(data) { var response = new ROSLIB.ServiceResponse(data); callback(response); }); @@ -42,9 +42,9 @@ ROSLIB.Service = function(options) { var call = { op : 'call_service', id : serviceCallId, - service : that.name, + service : service.name, args : requestValues }; - that.ros.callOnConnection(call); + service.ros.callOnConnection(call); }; }; diff --git a/src/core/ServiceRequest.js b/src/core/ServiceRequest.js index 7a6fe52fb..505200c44 100644 --- a/src/core/ServiceRequest.js +++ b/src/core/ServiceRequest.js @@ -9,10 +9,10 @@ * @param values - object matching the values of the request part from the .srv file. */ ROSLIB.ServiceRequest = function(values) { - var that = this; + var serviceRequest = this; if (values) { Object.keys(values).forEach(function(name) { - that[name] = values[name]; + serviceRequest[name] = values[name]; }); } }; diff --git a/src/core/ServiceResponse.js b/src/core/ServiceResponse.js index c577ed4cd..8e612f474 100644 --- a/src/core/ServiceResponse.js +++ b/src/core/ServiceResponse.js @@ -9,10 +9,10 @@ * @param values - object matching the values of the response part from the .srv file. */ ROSLIB.ServiceResponse = function(values) { - var that = this; + var serviceResponse = this; if (values) { Object.keys(values).forEach(function(name) { - that[name] = values[name]; + serviceResponse[name] = values[name]; }); } }; diff --git a/src/core/Topic.js b/src/core/Topic.js index 4dd70af07..2d0532628 100644 --- a/src/core/Topic.js +++ b/src/core/Topic.js @@ -18,7 +18,7 @@ * * throttle_rate - the rate at which to throttle the topics */ ROSLIB.Topic = function(options) { - var that = this; + var topic = this; options = options || {}; this.ros = options.ros; this.name = options.name; @@ -47,27 +47,27 @@ ROSLIB.Topic = function(options) { * * message - the published message */ this.subscribe = function(callback) { - that.on('message', function(message) { + topic.on('message', function(message) { callback(message); }); - that.ros.on(that.name, function(data) { + topic.ros.on(topic.name, function(data) { var message = new ROSLIB.Message(data); - that.emit('message', message); + topic.emit('message', message); }); - that.ros.idCounter++; - var subscribeId = 'subscribe:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var subscribeId = 'subscribe:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'subscribe', id : subscribeId, - type : that.messageType, - topic : that.name, - compression : that.compression, - throttle_rate : that.throttle_rate + type : topic.messageType, + topic : topic.name, + compression : topic.compression, + throttle_rate : topic.throttle_rate }; - that.ros.callOnConnection(call); + topic.ros.callOnConnection(call); }; /** @@ -75,46 +75,46 @@ ROSLIB.Topic = function(options) { * all subscribe callbacks. */ this.unsubscribe = function() { - that.ros.removeAllListeners([ that.name ]); - that.ros.idCounter++; - var unsubscribeId = 'unsubscribe:' + that.name + ':' + that.ros.idCounter; + topic.ros.removeAllListeners([ topic.name ]); + topic.ros.idCounter++; + var unsubscribeId = 'unsubscribe:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'unsubscribe', id : unsubscribeId, - topic : that.name + topic : topic.name }; - that.ros.callOnConnection(call); + topic.ros.callOnConnection(call); }; /** * Registers as a publisher for the topic. */ this.advertise = function() { - that.ros.idCounter++; - var advertiseId = 'advertise:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var advertiseId = 'advertise:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'advertise', id : advertiseId, - type : that.messageType, - topic : that.name + type : topic.messageType, + topic : topic.name }; - that.ros.callOnConnection(call); - that.isAdvertised = true; + topic.ros.callOnConnection(call); + topic.isAdvertised = true; }; /** * Unregisters as a publisher for the topic. */ this.unadvertise = function() { - that.ros.idCounter++; - var unadvertiseId = 'unadvertise:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var unadvertiseId = 'unadvertise:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'unadvertise', id : unadvertiseId, - topic : that.name + topic : topic.name }; - that.ros.callOnConnection(call); - that.isAdvertised = false; + topic.ros.callOnConnection(call); + topic.isAdvertised = false; }; /** @@ -123,19 +123,19 @@ ROSLIB.Topic = function(options) { * @param message - A ROSLIB.Message object. */ this.publish = function(message) { - if (!that.isAdvertised) { - that.advertise(); + if (!topic.isAdvertised) { + topic.advertise(); } - that.ros.idCounter++; - var publishId = 'publish:' + that.name + ':' + that.ros.idCounter; + topic.ros.idCounter++; + var publishId = 'publish:' + topic.name + ':' + topic.ros.idCounter; var call = { op : 'publish', id : publishId, - topic : that.name, + topic : topic.name, msg : message }; - that.ros.callOnConnection(call); + topic.ros.callOnConnection(call); }; }; ROSLIB.Topic.prototype.__proto__ = EventEmitter2.prototype;