From 5374470f94d5a9cb178294c335142d3266dec4d7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mathieu=20Br=C3=A9dif?= Date: Mon, 16 Apr 2018 17:51:46 +0200 Subject: [PATCH] fix: pointRatio option in PointCloud2 and LaserScan --- build/ros3d.js | 97 +------------------------------------- build/ros3d.min.js | 4 +- src/sensors/LaserScan.js | 2 +- src/sensors/PointCloud2.js | 2 +- 4 files changed, 6 insertions(+), 99 deletions(-) diff --git a/build/ros3d.js b/build/ros3d.js index 6e75b7df..394c8140 100644 --- a/build/ros3d.js +++ b/build/ros3d.js @@ -3570,7 +3570,7 @@ ROS3D.LaserScan.prototype.processMessage = function(message){ } var n = message.ranges.length; var j = 0; - for(var i=0;i= message.range_min && range <= message.range_max){ var angle = message.angle_min + i * message.angle_increment; @@ -3632,99 +3632,6 @@ ROS3D.NavSatFix = function(options) { ROS3D.NavSatFix.prototype.__proto__ = THREE.Object3D.prototype; -ROS3D.NavSatFix.prototype.unsubscribe = function(){ - if(this.rosTopic){ - this.rosTopic.unsubscribe(); - } -}; - -ROS3D.NavSatFix.prototype.subscribe = function(){ - this.unsubscribe(); - - // subscribe to the topic - this.rosTopic = new ROSLIB.Topic({ - ros : this.ros, - name : this.topicName, - messageType : 'sensor_msgs/NavSatFix' - }); - - this.rosTopic.subscribe(this.processMessage.bind(this)); -}; - -ROS3D.NavSatFix.prototype.processMessage = function(message){ - var altitude = isNaN(message.altitude) ? this.altitudeNaN : message.altitude; - var pt = this.convert(message.longitude, message.latitude, altitude); - - // move the object3d to the gps position - this.object3d.position.copy(pt); - this.object3d.updateMatrixWorld(true); - - // copy the position twice in the circular buffer - // the second half replicates the first to allow a single drawRange - this.vertices.array[3*this.next1 ] = pt.x; - this.vertices.array[3*this.next1+1] = pt.y; - this.vertices.array[3*this.next1+2] = pt.z; - this.vertices.array[3*this.next2 ] = pt.x; - this.vertices.array[3*this.next2+1] = pt.y; - this.vertices.array[3*this.next2+2] = pt.z; - this.vertices.needsUpdate = true; - - this.next1 = (this.next1+1) % this.keep; - this.next2 = this.next1 + this.keep; - this.count = Math.min(this.count+1, this.keep); - this.geom.setDrawRange(this.next2-this.count, this.count ); -}; - -/** - * @author Mathieu Bredif - mathieu.bredif@ign.fr - */ - -/** - * A NavSatFix client that listens to a given topic and displays a line connecting the gps fixes. - * - * @constructor - * @param options - object with following keys: - * - * * ros - the ROSLIB.Ros connection handle - * * topic - the NavSatFix topic to listen to - * * rootObject (optional) - the root object to add the trajectory line and the gps marker to - * * object3d (optional) - the object3d to be translated by the gps position - * * material (optional) - THREE.js material or options passed to a THREE.LineBasicMaterial, such as : - * * material.color (optional) - color for line - * * material.linewidth (optional) - line width - * * altitudeNaN (optional) - default altitude when the message altitude is NaN (default: 0) - * * keep (optional) - number of gps fix points to keep (default: 100) - * * convert (optional) - conversion function from lon/lat/alt to THREE.Vector3 (default: passthrough) - */ - -ROS3D.NavSatFix = function(options) { - options = options || {}; - this.ros = options.ros; - this.topicName = options.topic || '/gps/fix'; - this.rootObject = options.rootObject || new THREE.Object3D(); - this.object3d = options.object3d || new THREE.Object3D(); - var material = options.material || {}; - this.altitudeNaN = options.altitudeNaN || 0; - this.keep = options.keep || 100; - this.convert = options.convert || function(lon,lat,alt) { return new THREE.Vector3(lon,lat,alt); }; - this.count = 0; - this.next1 = 0; - this.next2 = this.keep; - - this.geom = new THREE.BufferGeometry(); - this.vertices = new THREE.BufferAttribute(new Float32Array( 6 * this.keep ), 3 ); - this.geom.addAttribute( 'position', this.vertices); - this.material = material.isMaterial ? material : new THREE.LineBasicMaterial( material ); - this.line = new THREE.Line( this.geom, this.material ); - this.rootObject.add(this.object3d); - this.rootObject.add(this.line); - - this.rosTopic = undefined; - this.subscribe(); -}; -ROS3D.NavSatFix.prototype.__proto__ = THREE.Object3D.prototype; - - ROS3D.NavSatFix.prototype.unsubscribe = function(){ if(this.rosTopic){ this.rosTopic.unsubscribe(); @@ -3860,7 +3767,7 @@ ROS3D.PointCloud2.prototype.processMessage = function(msg){ return; } - var n, pointRatio = this.points.positionRatio; + var n, pointRatio = this.points.pointRatio; if (msg.data.buffer) { this.points.buffer = msg.data.buffer; diff --git a/build/ros3d.min.js b/build/ros3d.min.js index 0e6c9e0d..6fee9350 100644 --- a/build/ros3d.min.js +++ b/build/ros3d.min.js @@ -1,3 +1,3 @@ function decode64(a,b,c,d){var e,f=0,g=0,h=0,i=a.length,j=b.length;c=c||j,d=d||1;var k=(d-1)*c*8;for(e=0;e=8&&(g-=8,b[h++]=f>>>g&255,h%c==0&&(e+=Math.ceil((k-g)/6),(g%=8)>0&&(f=decode64.e[a.charAt(e)])));return Math.floor(h/c)}var ROS3D=ROS3D||{REVISION:"0.18.0"};ROS3D.MARKER_ARROW=0,ROS3D.MARKER_CUBE=1,ROS3D.MARKER_SPHERE=2,ROS3D.MARKER_CYLINDER=3,ROS3D.MARKER_LINE_STRIP=4,ROS3D.MARKER_LINE_LIST=5,ROS3D.MARKER_CUBE_LIST=6,ROS3D.MARKER_SPHERE_LIST=7,ROS3D.MARKER_POINTS=8,ROS3D.MARKER_TEXT_VIEW_FACING=9,ROS3D.MARKER_MESH_RESOURCE=10,ROS3D.MARKER_TRIANGLE_LIST=11,ROS3D.INTERACTIVE_MARKER_KEEP_ALIVE=0,ROS3D.INTERACTIVE_MARKER_POSE_UPDATE=1,ROS3D.INTERACTIVE_MARKER_MENU_SELECT=2,ROS3D.INTERACTIVE_MARKER_BUTTON_CLICK=3,ROS3D.INTERACTIVE_MARKER_MOUSE_DOWN=4,ROS3D.INTERACTIVE_MARKER_MOUSE_UP=5,ROS3D.INTERACTIVE_MARKER_NONE=0,ROS3D.INTERACTIVE_MARKER_MENU=1,ROS3D.INTERACTIVE_MARKER_BUTTON=2,ROS3D.INTERACTIVE_MARKER_MOVE_AXIS=3,ROS3D.INTERACTIVE_MARKER_MOVE_PLANE=4,ROS3D.INTERACTIVE_MARKER_ROTATE_AXIS=5,ROS3D.INTERACTIVE_MARKER_MOVE_ROTATE=6,ROS3D.INTERACTIVE_MARKER_INHERIT=0,ROS3D.INTERACTIVE_MARKER_FIXED=1,ROS3D.INTERACTIVE_MARKER_VIEW_FACING=2,ROS3D.makeColorMaterial=function(a,b,c,d){var e=new THREE.Color;return e.setRGB(a,b,c),d<=.99?new THREE.MeshBasicMaterial({color:e.getHex(),opacity:d+.1,transparent:!0,depthWrite:!0,blendSrc:THREE.SrcAlphaFactor,blendDst:THREE.OneMinusSrcAlphaFactor,blendEquation:THREE.ReverseSubtractEquation,blending:THREE.NormalBlending}):new THREE.MeshPhongMaterial({color:e.getHex(),opacity:d,blending:THREE.NormalBlending})},ROS3D.intersectPlane=function(a,b,c){var d=new THREE.Vector3,e=new THREE.Vector3;d.subVectors(b,a.origin);var f=a.direction.dot(c);if(!(Math.abs(f)0.99)"," {"," vec4 depthColor2 = texture2D( map, vUv2 );"," float depth2 = ( depthColor2.r + depthColor2.g + depthColor2.b ) / 3.0 ;"," depth = 0.99+depth2;"," }"," "," return depth;"," }","","float median(float a, float b, float c)"," {"," float r=a;"," "," if ( (a0.5) || (vUvP.y<0.5) || (vUvP.y>0.0))"," {"," vec2 smp = decodeDepth(vec2(position.x, position.y));"," float depth = smp.x;"," depthVariance = smp.y;"," "," float z = -depth;"," "," pos = vec4("," ( position.x / width - 0.5 ) * z * 0.5 * maxDepthPerTile * (1000.0/focallength) * -1.0,"," ( position.y / height - 0.5 ) * z * 0.5 * maxDepthPerTile * (1000.0/focallength),"," (- z + zOffset / 1000.0) * maxDepthPerTile,"," 1.0);"," "," vec2 maskP = vec2( position.x / (width*2.0), position.y / (height*2.0) );"," vec4 maskColor = texture2D( map, maskP );"," maskVal = ( maskColor.r + maskColor.g + maskColor.b ) / 3.0 ;"," }"," "," gl_PointSize = pointSize;"," gl_Position = projectionMatrix * modelViewMatrix * pos;"," ","}"].join("\n"),this.fragment_shader=["uniform sampler2D map;","uniform float varianceThreshold;","uniform float whiteness;","","varying vec2 vUvP;","varying vec2 colorP;","","varying float depthVariance;","varying float maskVal;","","","void main() {"," "," vec4 color;"," "," if ( (depthVariance>varianceThreshold) || (maskVal>0.5) ||(vUvP.x<0.0)|| (vUvP.x>0.5) || (vUvP.y<0.5) || (vUvP.y>1.0))"," { "," discard;"," }"," else "," {"," color = texture2D( map, colorP );"," "," float fader = whiteness /100.0;"," "," color.r = color.r * (1.0-fader)+ fader;"," "," color.g = color.g * (1.0-fader)+ fader;"," "," color.b = color.b * (1.0-fader)+ fader;"," "," color.a = 1.0;//smoothstep( 20000.0, -20000.0, gl_FragCoord.z / gl_FragCoord.w );"," }"," "," gl_FragColor = vec4( color.r, color.g, color.b, color.a );"," ","}"].join("\n")},ROS3D.DepthCloud.prototype.__proto__=THREE.Object3D.prototype,ROS3D.DepthCloud.prototype.metaLoaded=function(){this.metaLoaded=!0,this.initStreamer()},ROS3D.DepthCloud.prototype.initStreamer=function(){if(this.metaLoaded){this.texture=new THREE.Texture(this.video),this.geometry=new THREE.Geometry;for(var a=0,b=this.width*this.height;a0&&(this.menu=new ROS3D.InteractiveMarkerMenu({menuEntries:c.menuEntries,menuFontSize:c.menuFontSize}),this.menu.addEventListener("menu-select",function(a){b.dispatchEvent(a)}))},ROS3D.InteractiveMarker.prototype.__proto__=THREE.Object3D.prototype,ROS3D.InteractiveMarker.prototype.showMenu=function(a,b){this.menu&&this.menu.show(a,b)},ROS3D.InteractiveMarker.prototype.moveAxis=function(a,b,c){if(this.dragging){var d=a.currentControlOri,e=b.clone().applyQuaternion(d),f=this.dragStart.event3d.intersection.point,g=e.clone().applyQuaternion(this.dragStart.orientationWorld.clone()),h=new THREE.Ray(f,g),i=ROS3D.closestAxisPoint(h,c.camera,c.mousePos),j=new THREE.Vector3;j.addVectors(this.dragStart.position,e.clone().applyQuaternion(this.dragStart.orientation).multiplyScalar(i)),this.setPosition(a,j),c.stopPropagation()}},ROS3D.InteractiveMarker.prototype.movePlane=function(a,b,c){if(this.dragging){var d=a.currentControlOri,e=b.clone().applyQuaternion(d),f=this.dragStart.event3d.intersection.point,g=e.clone().applyQuaternion(this.dragStart.orientationWorld),h=ROS3D.intersectPlane(c.mouseRay,f,g),i=new THREE.Vector3;i.subVectors(h,f),i.add(this.dragStart.positionWorld),this.setPosition(a,i),c.stopPropagation()}},ROS3D.InteractiveMarker.prototype.rotateAxis=function(a,b,c){if(this.dragging){a.updateMatrixWorld();var d=a.currentControlOri,e=d.clone().multiply(b.clone()),f=new THREE.Vector3(1,0,0).applyQuaternion(e),g=this.dragStart.event3d.intersection.point,h=f.applyQuaternion(this.dragStart.orientationWorld),i=ROS3D.intersectPlane(c.mouseRay,g,h),j=new THREE.Ray(this.dragStart.positionWorld,h),k=ROS3D.intersectPlane(j,g,h),l=this.dragStart.orientationWorld.clone().multiply(e),m=l.clone().inverse();i.sub(k),i.applyQuaternion(m);var n=this.dragStart.event3d.intersection.point.clone();n.sub(k),n.applyQuaternion(m);var o=Math.atan2(i.y,i.z),p=Math.atan2(n.y,n.z),q=p-o,r=new THREE.Quaternion;r.setFromAxisAngle(f,q),this.setOrientation(a,r.multiply(this.dragStart.orientationWorld)),c.stopPropagation()}},ROS3D.InteractiveMarker.prototype.feedbackEvent=function(a,b){this.dispatchEvent({type:a,position:this.position.clone(),orientation:this.quaternion.clone(),controlName:b.name})},ROS3D.InteractiveMarker.prototype.startDrag=function(a,b){if(0===b.domEvent.button){b.stopPropagation(),this.dragging=!0,this.updateMatrixWorld(!0);var c=new THREE.Vector3;this.matrixWorld.decompose(this.dragStart.positionWorld,this.dragStart.orientationWorld,c),this.dragStart.position=this.position.clone(),this.dragStart.orientation=this.quaternion.clone(),this.dragStart.event3d=b,this.feedbackEvent("user-mousedown",a)}},ROS3D.InteractiveMarker.prototype.stopDrag=function(a,b){0===b.domEvent.button&&(b.stopPropagation(),this.dragging=!1,this.dragStart.event3d={},this.onServerSetPose(this.bufferedPoseEvent),this.bufferedPoseEvent=void 0,this.feedbackEvent("user-mouseup",a))},ROS3D.InteractiveMarker.prototype.buttonClick=function(a,b){b.stopPropagation(),this.feedbackEvent("user-button-click",a)},ROS3D.InteractiveMarker.prototype.setPosition=function(a,b){this.position.copy(b),this.feedbackEvent("user-pose-change",a)},ROS3D.InteractiveMarker.prototype.setOrientation=function(a,b){b.normalize(),this.quaternion.copy(b),this.feedbackEvent("user-pose-change",a)},ROS3D.InteractiveMarker.prototype.onServerSetPose=function(a){if(void 0!==a)if(this.dragging)this.bufferedPoseEvent=a;else{var b=a.pose;this.position.copy(b.position),this.quaternion.copy(b.orientation),this.updateMatrixWorld(!0)}},ROS3D.InteractiveMarker.prototype.dispose=function(){var a=this;this.children.forEach(function(b){b.children.forEach(function(a){a.dispose(),b.remove(a)}),a.remove(b)})},Object.assign(ROS3D.InteractiveMarker.prototype,THREE.EventDispatcher.prototype),ROS3D.InteractiveMarkerClient=function(a){a=a||{},this.ros=a.ros,this.tfClient=a.tfClient,this.topicName=a.topic,this.path=a.path||"/",this.camera=a.camera,this.rootObject=a.rootObject||new THREE.Object3D,this.loader=a.loader||ROS3D.COLLADA_LOADER_2,this.menuFontSize=a.menuFontSize||"0.8em",this.interactiveMarkers={},this.updateTopic=null,this.feedbackTopic=null,this.topicName&&this.subscribe(this.topicName)},ROS3D.InteractiveMarkerClient.prototype.subscribe=function(a){this.unsubscribe(),this.updateTopic=new ROSLIB.Topic({ros:this.ros,name:a+"/tunneled/update",messageType:"visualization_msgs/InteractiveMarkerUpdate",compression:"png"}),this.updateTopic.subscribe(this.processUpdate.bind(this)),this.feedbackTopic=new ROSLIB.Topic({ros:this.ros,name:a+"/feedback",messageType:"visualization_msgs/InteractiveMarkerFeedback",compression:"png"}),this.feedbackTopic.advertise(),this.initService=new ROSLIB.Service({ros:this.ros,name:a+"/tunneled/get_init",serviceType:"demo_interactive_markers/GetInit"});var b=new ROSLIB.ServiceRequest({});this.initService.callService(b,this.processInit.bind(this))},ROS3D.InteractiveMarkerClient.prototype.unsubscribe=function(){this.updateTopic&&this.updateTopic.unsubscribe(),this.feedbackTopic&&this.feedbackTopic.unadvertise();for(var a in this.interactiveMarkers)this.eraseIntMarker(a);this.interactiveMarkers={}},ROS3D.InteractiveMarkerClient.prototype.processInit=function(a){var b=a.msg;b.erases=[];for(var c in this.interactiveMarkers)b.erases.push(c);b.poses=[],this.processUpdate(b)},ROS3D.InteractiveMarkerClient.prototype.processUpdate=function(a){var b=this;a.erases.forEach(function(a){b.eraseIntMarker(a)}),a.poses.forEach(function(a){var c=b.interactiveMarkers[a.name];c&&c.setPoseFromServer(a.pose)}),a.markers.forEach(function(a){var c=b.interactiveMarkers[a.name];c&&b.eraseIntMarker(c.name);var d=new ROS3D.InteractiveMarkerHandle({message:a,feedbackTopic:b.feedbackTopic,tfClient:b.tfClient,menuFontSize:b.menuFontSize});b.interactiveMarkers[a.name]=d;var e=new ROS3D.InteractiveMarker({handle:d,camera:b.camera,path:b.path,loader:b.loader});e.name=a.name,b.rootObject.add(e),d.on("pose",function(a){e.onServerSetPose({pose:a})}),e.addEventListener("user-pose-change",d.setPoseFromClientBound),e.addEventListener("user-mousedown",d.onMouseDownBound),e.addEventListener("user-mouseup",d.onMouseUpBound),e.addEventListener("user-button-click",d.onButtonClickBound),e.addEventListener("menu-select",d.onMenuSelectBound),d.subscribeTf()})},ROS3D.InteractiveMarkerClient.prototype.eraseIntMarker=function(a){if(this.interactiveMarkers[a]){var b=this.rootObject.getObjectByName(a);this.rootObject.remove(b);var c=this.interactiveMarkers[a];c.unsubscribeTf(),b.removeEventListener("user-pose-change",c.setPoseFromClientBound),b.removeEventListener("user-mousedown",c.onMouseDownBound),b.removeEventListener("user-mouseup",c.onMouseUpBound),b.removeEventListener("user-button-click",c.onButtonClickBound),b.removeEventListener("menu-select",c.onMenuSelectBound),delete this.interactiveMarkers[a],b.dispose()}},ROS3D.InteractiveMarkerControl=function(a){function b(a){a.stopPropagation()}var c=this;THREE.Object3D.call(this),a=a||{},this.parent=a.parent;var d=a.handle,e=a.message;this.name=e.name,this.camera=a.camera,this.path=a.path||"/",this.loader=a.loader||ROS3D.COLLADA_LOADER_2,this.dragging=!1,this.startMousePos=new THREE.Vector2;var f=new THREE.Quaternion(e.orientation.x,e.orientation.y,e.orientation.z,e.orientation.w);f.normalize();var g=new THREE.Vector3(1,0,0);switch(g.applyQuaternion(f),this.currentControlOri=new THREE.Quaternion,e.interaction_mode){case ROS3D.INTERACTIVE_MARKER_MOVE_AXIS:this.addEventListener("mousemove",this.parent.moveAxis.bind(this.parent,this,g)),this.addEventListener("touchmove",this.parent.moveAxis.bind(this.parent,this,g));break;case ROS3D.INTERACTIVE_MARKER_ROTATE_AXIS:this.addEventListener("mousemove",this.parent.rotateAxis.bind(this.parent,this,f));break;case ROS3D.INTERACTIVE_MARKER_MOVE_PLANE:this.addEventListener("mousemove",this.parent.movePlane.bind(this.parent,this,g));break;case ROS3D.INTERACTIVE_MARKER_BUTTON:this.addEventListener("click",this.parent.buttonClick.bind(this.parent,this))}e.interaction_mode!==ROS3D.INTERACTIVE_MARKER_NONE&&(this.addEventListener("mousedown",this.parent.startDrag.bind(this.parent,this)),this.addEventListener("mouseup",this.parent.stopDrag.bind(this.parent,this)),this.addEventListener("contextmenu",this.parent.showMenu.bind(this.parent,this)),this.addEventListener("mouseup",function(a){0===c.startMousePos.distanceToSquared(a.mousePos)&&(a.type="contextmenu",c.dispatchEvent(a))}),this.addEventListener("mouseover",b),this.addEventListener("mouseout",b),this.addEventListener("click",b),this.addEventListener("mousedown",function(a){c.startMousePos=a.mousePos}),this.addEventListener("touchstart",function(a){1===a.domEvent.touches.length&&(a.type="mousedown",a.domEvent.button=0,c.dispatchEvent(a))}),this.addEventListener("touchmove",function(a){1===a.domEvent.touches.length&&(a.type="mousemove",a.domEvent.button=0,c.dispatchEvent(a))}),this.addEventListener("touchend",function(a){0===a.domEvent.touches.length&&(a.domEvent.button=0,a.type="mouseup",c.dispatchEvent(a),a.type="click",c.dispatchEvent(a))}));var h=new THREE.Quaternion,i=this.parent.position.clone().multiplyScalar(-1);switch(e.orientation_mode){case ROS3D.INTERACTIVE_MARKER_INHERIT:h=this.parent.quaternion.clone().inverse(),this.updateMatrixWorld=function(a){ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(c,a),c.currentControlOri.copy(c.quaternion),c.currentControlOri.normalize()};break;case ROS3D.INTERACTIVE_MARKER_FIXED:this.updateMatrixWorld=function(a){c.quaternion.copy(c.parent.quaternion.clone().inverse()),c.updateMatrix(),c.matrixWorldNeedsUpdate=!0,ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(c,a),c.currentControlOri.copy(c.quaternion)};break;case ROS3D.INTERACTIVE_MARKER_VIEW_FACING:var j=e.independent_marker_orientation;this.updateMatrixWorld=function(a){c.camera.updateMatrixWorld();var b=(new THREE.Matrix4).extractRotation(c.camera.matrixWorld),d=new THREE.Matrix4,e=.5*Math.PI,f=new THREE.Euler(-e,0,e);d.makeRotationFromEuler(f);var g=new THREE.Matrix4;g.getInverse(c.parent.matrixWorld),b.multiplyMatrices(b,d),b.multiplyMatrices(g,b),c.currentControlOri.setFromRotationMatrix(b),j||(c.quaternion.copy(c.currentControlOri),c.updateMatrix(),c.matrixWorldNeedsUpdate=!0),ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(c,a)};break;default:console.error("Unkown orientation mode: "+e.orientation_mode)}var k=new ROSLIB.TFClient({ros:d.tfClient.ros,fixedFrame:d.message.header.frame_id,serverName:d.tfClient.serverName});e.markers.forEach(function(a){var b=function(b){var d=new ROS3D.Marker({message:a,path:c.path,loader:c.loader});if(null!==b){var e=new ROSLIB.Pose({position:d.position,orientation:d.quaternion});e.applyTransform(new ROSLIB.Transform(b));var f=new ROS3D.Marker({message:a,path:c.path,loader:c.loader});f.position.add(i),f.position.applyQuaternion(h),f.quaternion.multiplyQuaternions(h,f.quaternion);var g=new THREE.Vector3(f.position.x,f.position.y,f.position.z),j=new ROSLIB.Transform({translation:g,orientation:f.quaternion});e.applyTransform(j),d.setPose(e),d.updateMatrixWorld(),k.unsubscribe(a.header.frame_id)}c.add(d)};""!==a.header.frame_id?k.subscribe(a.header.frame_id,b):b(null)})},ROS3D.InteractiveMarkerControl.prototype.__proto__=THREE.Object3D.prototype,ROS3D.InteractiveMarkerHandle=function(a){a=a||{},this.message=a.message,this.feedbackTopic=a.feedbackTopic,this.tfClient=a.tfClient,this.menuFontSize=a.menuFontSize||"0.8em",this.name=this.message.name,this.header=this.message.header,this.controls=this.message.controls,this.menuEntries=this.message.menu_entries,this.dragging=!1,this.timeoutHandle=null,this.tfTransform=new ROSLIB.Transform,this.pose=new ROSLIB.Pose,this.setPoseFromClientBound=this.setPoseFromClient.bind(this),this.onMouseDownBound=this.onMouseDown.bind(this),this.onMouseUpBound=this.onMouseUp.bind(this),this.onButtonClickBound=this.onButtonClick.bind(this),this.onMenuSelectBound=this.onMenuSelect.bind(this),this.setPoseFromServer(this.message.pose),this.tfUpdateBound=this.tfUpdate.bind(this)},ROS3D.InteractiveMarkerHandle.prototype.__proto__=EventEmitter2.prototype,ROS3D.InteractiveMarkerHandle.prototype.subscribeTf=function(){0===this.message.header.stamp.secs&&0===this.message.header.stamp.nsecs&&this.tfClient.subscribe(this.message.header.frame_id,this.tfUpdateBound)},ROS3D.InteractiveMarkerHandle.prototype.unsubscribeTf=function(){this.tfClient.unsubscribe(this.message.header.frame_id,this.tfUpdateBound)},ROS3D.InteractiveMarkerHandle.prototype.emitServerPoseUpdate=function(){var a=new ROSLIB.Pose(this.pose);a.applyTransform(this.tfTransform),this.emit("pose",a)},ROS3D.InteractiveMarkerHandle.prototype.setPoseFromServer=function(a){this.pose=new ROSLIB.Pose(a),this.emitServerPoseUpdate()},ROS3D.InteractiveMarkerHandle.prototype.tfUpdate=function(a){this.tfTransform=new ROSLIB.Transform(a),this.emitServerPoseUpdate()},ROS3D.InteractiveMarkerHandle.prototype.setPoseFromClient=function(a){this.pose=new ROSLIB.Pose(a);var b=this.tfTransform.clone();b.rotation.invert(),b.translation.multiplyQuaternion(b.rotation),b.translation.x*=-1,b.translation.y*=-1,b.translation.z*=-1,this.pose.applyTransform(b),this.sendFeedback(ROS3D.INTERACTIVE_MARKER_POSE_UPDATE,void 0,0,a.controlName),this.dragging&&(this.timeoutHandle&&clearTimeout(this.timeoutHandle),this.timeoutHandle=setTimeout(this.setPoseFromClient.bind(this,a),250))},ROS3D.InteractiveMarkerHandle.prototype.onButtonClick=function(a){this.sendFeedback(ROS3D.INTERACTIVE_MARKER_BUTTON_CLICK,a.clickPosition,0,a.controlName)},ROS3D.InteractiveMarkerHandle.prototype.onMouseDown=function(a){this.sendFeedback(ROS3D.INTERACTIVE_MARKER_MOUSE_DOWN,a.clickPosition,0,a.controlName),this.dragging=!0},ROS3D.InteractiveMarkerHandle.prototype.onMouseUp=function(a){this.sendFeedback(ROS3D.INTERACTIVE_MARKER_MOUSE_UP,a.clickPosition,0,a.controlName),this.dragging=!1,this.timeoutHandle&&clearTimeout(this.timeoutHandle)},ROS3D.InteractiveMarkerHandle.prototype.onMenuSelect=function(a){this.sendFeedback(ROS3D.INTERACTIVE_MARKER_MENU_SELECT,void 0,a.id,a.controlName)},ROS3D.InteractiveMarkerHandle.prototype.sendFeedback=function(a,b,c,d){var e=void 0!==b;b=b||{x:0,y:0,z:0};var f={header:this.header,client_id:this.clientID,marker_name:this.name,control_name:d,event_type:a,pose:this.pose,mouse_point:b,mouse_point_valid:e,menu_entry_id:c};this.feedbackTopic.publish(f)},ROS3D.InteractiveMarkerMenu=function(a){function b(a,b){this.dispatchEvent({type:"menu-select",domEvent:b,id:a.id,controlName:this.controlName}),this.hide(b)}function c(a,e){var f=document.createElement("ul");a.appendChild(f);for(var g=e.children,h=0;h0?(c(i,g[h]),j.addEventListener("click",d.hide.bind(d)),j.addEventListener("touchstart",d.hide.bind(d))):(j.addEventListener("click",b.bind(d,g[h])),j.addEventListener("touchstart",b.bind(d,g[h])),j.className="default-interactive-marker-menu-entry")}}var d=this;a=a||{};var e=a.menuEntries,f=a.className||"default-interactive-marker-menu",g=(a.entryClassName,a.overlayClassName||"default-interactive-marker-overlay"),h=a.menuFontSize||"0.8em",i=[];if(i[0]={children:[]},THREE.EventDispatcher.call(this),null===document.getElementById("default-interactive-marker-menu-css")){var j=document.createElement("style");j.id="default-interactive-marker-menu-css",j.type="text/css",j.innerHTML=".default-interactive-marker-menu {background-color: #444444;border: 1px solid #888888;border: 1px solid #888888;padding: 0px 0px 0px 0px;color: #FFFFFF;font-family: sans-serif;font-size: "+h+";z-index: 1002;}.default-interactive-marker-menu ul {padding: 0px 0px 5px 0px;margin: 0px;list-style-type: none;}.default-interactive-marker-menu ul li div {-webkit-touch-callout: none;-webkit-user-select: none;-khtml-user-select: none;-moz-user-select: none;-ms-user-select: none;user-select: none;cursor: default;padding: 3px 10px 3px 10px;}.default-interactive-marker-menu-entry:hover { background-color: #666666; cursor: pointer;}.default-interactive-marker-menu ul ul { font-style: italic; padding-left: 10px;}.default-interactive-marker-overlay { position: absolute; top: 0%; left: 0%; width: 100%; height: 100%; background-color: black; z-index: 1001; -moz-opacity: 0.0; opacity: .0; filter: alpha(opacity = 0);}",document.getElementsByTagName("head")[0].appendChild(j)}this.menuDomElem=document.createElement("div"),this.menuDomElem.style.position="absolute",this.menuDomElem.className=f,this.menuDomElem.addEventListener("contextmenu",function(a){a.preventDefault()}),this.overlayDomElem=document.createElement("div"),this.overlayDomElem.className=g,this.hideListener=this.hide.bind(this),this.overlayDomElem.addEventListener("contextmenu",this.hideListener),this.overlayDomElem.addEventListener("click",this.hideListener),this.overlayDomElem.addEventListener("touchstart",this.hideListener);var k,l,m;for(k=0;k0){var V=this.msgColor,W=document.createElement("canvas"),X=W.getContext("2d");X.font="normal 100px sans-serif";var Y=X.measureText(c.text),Z=Y.width;W.width=Z,W.height=150,X.font="normal 100px sans-serif",X.fillStyle="rgba("+Math.round(255*V.r)+", "+Math.round(255*V.g)+", "+Math.round(255*V.b)+", "+V.a+")",X.textAlign="left",X.textBaseline="middle",X.fillText(c.text,0,W.height/2);var $=new THREE.Texture(W);$.needsUpdate=!0 -;var _=new THREE.SpriteMaterial({map:$,useScreenCoordinates:!1}),aa=new THREE.Sprite(_),ba=c.scale.x;aa.scale.set(Z/W.height*ba,ba,1),this.add(aa)}break;case ROS3D.MARKER_MESH_RESOURCE:var ca=null;0===c.color.r&&0===c.color.g&&0===c.color.b&&0===c.color.a||(ca=d),this.msgMesh=c.mesh_resource.substr(10);var da=new ROS3D.MeshResource({path:b,resource:this.msgMesh,material:ca});this.add(da);break;case ROS3D.MARKER_TRIANGLE_LIST:var ea=new ROS3D.TriangleList({material:d,vertices:c.points,colors:c.colors});ea.scale.set(c.scale.x,c.scale.y,c.scale.z),this.add(ea);break;default:console.error("Currently unsupported marker type: "+c.type)}},ROS3D.Marker.prototype.__proto__=THREE.Object3D.prototype,ROS3D.Marker.prototype.setPose=function(a){this.position.x=a.position.x,this.position.y=a.position.y,this.position.z=a.position.z,this.quaternion.set(a.orientation.x,a.orientation.y,a.orientation.z,a.orientation.w),this.quaternion.normalize(),this.updateMatrixWorld()},ROS3D.Marker.prototype.update=function(a){if(this.setPose(a.pose),a.color.r!==this.msgColor.r||a.color.g!==this.msgColor.g||a.color.b!==this.msgColor.b||a.color.a!==this.msgColor.a){var b=ROS3D.makeColorMaterial(a.color.r,a.color.g,a.color.b,a.color.a);switch(a.type){case ROS3D.MARKER_LINE_STRIP:case ROS3D.MARKER_LINE_LIST:case ROS3D.MARKER_POINTS:break;case ROS3D.MARKER_ARROW:case ROS3D.MARKER_CUBE:case ROS3D.MARKER_SPHERE:case ROS3D.MARKER_CYLINDER:case ROS3D.MARKER_TRIANGLE_LIST:case ROS3D.MARKER_TEXT_VIEW_FACING:this.traverse(function(a){a instanceof THREE.Mesh&&(a.material=b)});break;case ROS3D.MARKER_MESH_RESOURCE:var c=null;0===a.color.r&&0===a.color.g&&0===a.color.b&&0===a.color.a||(c=this.colorMaterial),this.traverse(function(a){a instanceof THREE.Mesh&&(a.material=c)});break;case ROS3D.MARKER_CUBE_LIST:case ROS3D.MARKER_SPHERE_LIST:default:return!1}this.msgColor=a.color}var d=Math.abs(this.msgScale[0]-a.scale.x)>1e-6||Math.abs(this.msgScale[1]-a.scale.y)>1e-6||Math.abs(this.msgScale[2]-a.scale.z)>1e-6;switch(this.msgScale=[a.scale.x,a.scale.y,a.scale.z],a.type){case ROS3D.MARKER_CUBE:case ROS3D.MARKER_SPHERE:case ROS3D.MARKER_CYLINDER:if(d)return!1;break;case ROS3D.MARKER_TEXT_VIEW_FACING:if(d||this.text!==a.text)return!1;break;case ROS3D.MARKER_MESH_RESOURCE:if(a.mesh_resource.substr(10)!==this.msgMesh)return!1;if(d)return!1;break;case ROS3D.MARKER_ARROW:case ROS3D.MARKER_LINE_STRIP:case ROS3D.MARKER_LINE_LIST:case ROS3D.MARKER_CUBE_LIST:case ROS3D.MARKER_SPHERE_LIST:case ROS3D.MARKER_POINTS:case ROS3D.MARKER_TRIANGLE_LIST:return!1}return!0},ROS3D.Marker.prototype.dispose=function(){this.children.forEach(function(a){a instanceof ROS3D.MeshResource?a.children.forEach(function(b){void 0!==b.material&&b.material.dispose(),b.children.forEach(function(a){void 0!==a.geometry&&a.geometry.dispose(),void 0!==a.material&&a.material.dispose(),b.remove(a)}),a.remove(b)}):(void 0!==a.geometry&&a.geometry.dispose(),void 0!==a.material&&a.material.dispose()),a.parent.remove(a)})},ROS3D.MarkerArrayClient=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic,this.tfClient=a.tfClient,this.rootObject=a.rootObject||new THREE.Object3D,this.path=a.path||"/",this.markers={},this.rosTopic=void 0,this.subscribe()},ROS3D.MarkerArrayClient.prototype.__proto__=EventEmitter2.prototype,ROS3D.MarkerArrayClient.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"visualization_msgs/MarkerArray",compression:"png"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.MarkerArrayClient.prototype.processMessage=function(a){a.markers.forEach(function(a){if(0===a.action){var b=!1;if(a.ns+a.id in this.markers&&((b=this.markers[a.ns+a.id].children[0].update(a))||(this.markers[a.ns+a.id].unsubscribeTf(),this.rootObject.remove(this.markers[a.ns+a.id]))),!b){var c=new ROS3D.Marker({message:a,path:this.path});this.markers[a.ns+a.id]=new ROS3D.SceneNode({frameID:a.header.frame_id,tfClient:this.tfClient,object:c}),this.rootObject.add(this.markers[a.ns+a.id])}}else if(1===a.action)console.warn('Received marker message with deprecated action identifier "1"');else if(2===a.action)this.markers[a.ns+a.id].unsubscribeTf(),this.rootObject.remove(this.markers[a.ns+a.id]),delete this.markers[a.ns+a.id];else if(3===a.action){for(var d in this.markers)this.markers[d].unsubscribeTf(),this.rootObject.remove(this.markers[d]);this.markers={}}else console.warn('Received marker message with unknown action identifier "'+a.action+'"')}.bind(this)),this.emit("change")},ROS3D.MarkerArrayClient.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.MarkerClient=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic,this.tfClient=a.tfClient,this.rootObject=a.rootObject||new THREE.Object3D,this.path=a.path||"/",this.markers={},this.rosTopic=void 0,this.subscribe()},ROS3D.MarkerClient.prototype.__proto__=EventEmitter2.prototype,ROS3D.MarkerClient.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.MarkerClient.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"visualization_msgs/Marker",compression:"png"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.MarkerClient.prototype.processMessage=function(a){var b=new ROS3D.Marker({message:a,path:this.path}),c=this.markers[a.ns+a.id];c&&(c.unsubscribeTf(),this.rootObject.remove(c)),this.markers[a.ns+a.id]=new ROS3D.SceneNode({frameID:a.header.frame_id,tfClient:this.tfClient,object:b}),this.rootObject.add(this.markers[a.ns+a.id]),this.emit("change")},ROS3D.Arrow=function(a){a=a||{};var b=a.origin||new THREE.Vector3(0,0,0),c=a.direction||new THREE.Vector3(1,0,0),d=a.length||1,e=a.headLength||.2,f=a.shaftDiameter||.05,g=a.headDiameter||.1,h=a.material||new THREE.MeshBasicMaterial,i=d-e,j=new THREE.CylinderGeometry(.5*f,.5*f,i,12,1),k=new THREE.Matrix4;k.setPosition(new THREE.Vector3(0,.5*i,0)),j.applyMatrix(k);var l=new THREE.CylinderGeometry(0,.5*g,e,12,1);k.setPosition(new THREE.Vector3(0,i+.5*e,0)),l.applyMatrix(k),j.merge(l),THREE.Mesh.call(this,j,h),this.position.copy(b),this.setDirection(c)},ROS3D.Arrow.prototype.__proto__=THREE.Mesh.prototype,ROS3D.Arrow.prototype.setDirection=function(a){var b=new THREE.Vector3(0,1,0).cross(a),c=Math.acos(new THREE.Vector3(0,1,0).dot(a.clone().normalize()));this.matrix=(new THREE.Matrix4).makeRotationAxis(b.normalize(),c),this.rotation.setFromRotationMatrix(this.matrix,this.rotation.order)},ROS3D.Arrow.prototype.setLength=function(a){this.scale.set(a,a,a)},ROS3D.Arrow.prototype.setColor=function(a){this.material.color.setHex(a)},ROS3D.Arrow.prototype.dispose=function(){void 0!==this.geometry&&this.geometry.dispose(),void 0!==this.material&&this.material.dispose()},ROS3D.Arrow2=function(a){a=a||{};var b=a.origin||new THREE.Vector3(0,0,0),c=a.direction||new THREE.Vector3(1,0,0),d=a.length||1;a.headLength,a.shaftDiameter,a.headDiameter,a.material||new THREE.MeshBasicMaterial;THREE.ArrowHelper.call(this,c,b,d,16711680)},ROS3D.Arrow2.prototype.__proto__=THREE.ArrowHelper.prototype,ROS3D.Arrow2.prototype.dispose=function(){void 0!==this.line&&(this.line.material.dispose(),this.line.geometry.dispose()),void 0!==this.cone&&(this.cone.material.dispose(),this.cone.geometry.dispose())},ROS3D.Axes=function(a){function b(a){var b=new THREE.Color;b.setRGB(a.x,a.y,a.z);var d=new THREE.MeshBasicMaterial({color:b.getHex()}),e=new THREE.Vector3;e.crossVectors(a,new THREE.Vector3(0,-1,0));var f=new THREE.Quaternion;f.setFromAxisAngle(e,.5*Math.PI);var g=new THREE.Mesh(c.headGeom,d);g.position.copy(a),g.position.multiplyScalar(.95),g.quaternion.copy(f),g.updateMatrix(),c.add(g);var h=new THREE.Mesh(c.lineGeom,d);h.position.copy(a),h.position.multiplyScalar(.45),h.quaternion.copy(f),h.updateMatrix(),c.add(h)}var c=this;a=a||{};var d=a.shaftRadius||.008,e=a.headRadius||.023,f=a.headLength||.1;THREE.Object3D.call(this),this.lineGeom=new THREE.CylinderGeometry(d,d,1-f),this.headGeom=new THREE.CylinderGeometry(0,e,f),b(new THREE.Vector3(1,0,0)),b(new THREE.Vector3(0,1,0)),b(new THREE.Vector3(0,0,1))},ROS3D.Axes.prototype.__proto__=THREE.Object3D.prototype,ROS3D.Grid=function(a){a=a||{};var b=a.num_cells||10,c=a.color||"#cccccc",d=a.lineWidth||1,e=a.cellSize||1;THREE.Object3D.call(this);for(var f=new THREE.LineBasicMaterial({color:c,linewidth:d}),g=0;g<=b;++g){var h=e*b/2,i=h-g*e,j=new THREE.Geometry;j.vertices.push(new THREE.Vector3(-h,i,0),new THREE.Vector3(h,i,0));var k=new THREE.Geometry;k.vertices.push(new THREE.Vector3(i,-h,0),new THREE.Vector3(i,h,0)),this.add(new THREE.Line(j,f)),this.add(new THREE.Line(k,f))}},ROS3D.Grid.prototype.__proto__=THREE.Object3D.prototype,ROS3D.MeshResource=function(a){var b=this;a=a||{};var c=a.path||"/",d=a.resource,e=a.material||null;this.warnings=a.warnings,THREE.Object3D.call(this),"/"!==c.substr(c.length-1)&&(c+="/");var f,g=c+d,h=g.substr(-4).toLowerCase();".dae"===h?(f=new THREE.ColladaLoader,f.log=function(a){b.warnings&&console.warn(a)},f.load(g,function(a){null!==e&&a.scene.traverse(function(a){a instanceof THREE.Mesh&&void 0===a.material&&(a.material=e)}),b.add(a.scene)},null,function(a){console.error(a)})):".stl"===h&&(f=new THREE.STLLoader,f.load(g,function(a){a.computeFaceNormals();var c;c=null!==e?new THREE.Mesh(a,e):new THREE.Mesh(a,new THREE.MeshBasicMaterial({color:10066329})),b.add(c)},null,function(a){console.error(a)}))},ROS3D.MeshResource.prototype.__proto__=THREE.Object3D.prototype,ROS3D.TriangleList=function(a){a=a||{};var b=a.material||new THREE.MeshBasicMaterial,c=a.vertices,d=a.colors;THREE.Object3D.call(this),b.side=THREE.DoubleSide;var e=new THREE.Geometry;for(f=0;f=this.keep&&(this.sns[0].unsubscribeTf(),this.rootObject.remove(this.sns[0]),this.sns.shift()),this.options.origin=new THREE.Vector3(a.pose.pose.position.x,a.pose.pose.position.y,a.pose.pose.position.z);var b=new THREE.Quaternion(a.pose.pose.orientation.x,a.pose.pose.orientation.y,a.pose.pose.orientation.z,a.pose.pose.orientation.w);this.options.direction=new THREE.Vector3(1,0,0),this.options.direction.applyQuaternion(b),this.options.material=new THREE.MeshBasicMaterial({color:this.color});var c=new ROS3D.Arrow(this.options);this.sns.push(new ROS3D.SceneNode({frameID:a.header.frame_id,tfClient:this.tfClient,object:c})),this.rootObject.add(this.sns[this.sns.length-1])},ROS3D.Path=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/path",this.tfClient=a.tfClient,this.color=a.color||13369599,this.rootObject=a.rootObject||new THREE.Object3D,THREE.Object3D.call(this),this.sn=null,this.line=null,this.rosTopic=void 0,this.subscribe()},ROS3D.Path.prototype.__proto__=THREE.Object3D.prototype,ROS3D.Path.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.Path.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"nav_msgs/Path"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.Path.prototype.processMessage=function(a){null!==this.sn&&(this.sn.unsubscribeTf(),this.rootObject.remove(this.sn));for(var b=new THREE.Geometry,c=0;c=a.range_min&&e<=a.range_max){var f=a.angle_min+d*a.angle_increment;this.points.positions.array[c++]=e*Math.cos(f),this.points.positions.array[c++]=e*Math.sin(f),this.points.positions.array[c++]=0}}this.points.update(c/3)}},ROS3D.NavSatFix=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/gps/fix",this.rootObject=a.rootObject||new THREE.Object3D,this.object3d=a.object3d||new THREE.Object3D;var b=a.material||{};this.altitudeNaN=a.altitudeNaN||0,this.keep=a.keep||100,this.convert=a.convert||function(a,b,c){return new THREE.Vector3(a,b,c)},this.count=0,this.next1=0,this.next2=this.keep,this.geom=new THREE.BufferGeometry,this.vertices=new THREE.BufferAttribute(new Float32Array(6*this.keep),3),this.geom.addAttribute("position",this.vertices),this.material=b.isMaterial?b:new THREE.LineBasicMaterial(b),this.line=new THREE.Line(this.geom,this.material),this.rootObject.add(this.object3d),this.rootObject.add(this.line),this.rosTopic=void 0,this.subscribe()},ROS3D.NavSatFix.prototype.__proto__=THREE.Object3D.prototype,ROS3D.NavSatFix.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.NavSatFix.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"sensor_msgs/NavSatFix"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.NavSatFix.prototype.processMessage=function(a){var b=isNaN(a.altitude)?this.altitudeNaN:a.altitude,c=this.convert(a.longitude,a.latitude,b);this.object3d.position.copy(c),this.object3d.updateMatrixWorld(!0),this.vertices.array[3*this.next1]=c.x,this.vertices.array[3*this.next1+1]=c.y,this.vertices.array[3*this.next1+2]=c.z,this.vertices.array[3*this.next2]=c.x,this.vertices.array[3*this.next2+1]=c.y,this.vertices.array[3*this.next2+2]=c.z,this.vertices.needsUpdate=!0,this.next1=(this.next1+1)%this.keep,this.next2=this.next1+this.keep,this.count=Math.min(this.count+1,this.keep),this.geom.setDrawRange(this.next2-this.count,this.count)},ROS3D.NavSatFix=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/gps/fix",this.rootObject=a.rootObject||new THREE.Object3D,this.object3d=a.object3d||new THREE.Object3D;var b=a.material||{};this.altitudeNaN=a.altitudeNaN||0,this.keep=a.keep||100,this.convert=a.convert||function(a,b,c){return new THREE.Vector3(a,b,c)},this.count=0,this.next1=0,this.next2=this.keep,this.geom=new THREE.BufferGeometry,this.vertices=new THREE.BufferAttribute(new Float32Array(6*this.keep),3),this.geom.addAttribute("position",this.vertices),this.material=b.isMaterial?b:new THREE.LineBasicMaterial(b),this.line=new THREE.Line(this.geom,this.material),this.rootObject.add(this.object3d),this.rootObject.add(this.line),this.rosTopic=void 0,this.subscribe()},ROS3D.NavSatFix.prototype.__proto__=THREE.Object3D.prototype,ROS3D.NavSatFix.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.NavSatFix.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"sensor_msgs/NavSatFix"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.NavSatFix.prototype.processMessage=function(a){var b=isNaN(a.altitude)?this.altitudeNaN:a.altitude,c=this.convert(a.longitude,a.latitude,b);this.object3d.position.copy(c),this.object3d.updateMatrixWorld(!0),this.vertices.array[3*this.next1]=c.x,this.vertices.array[3*this.next1+1]=c.y,this.vertices.array[3*this.next1+2]=c.z,this.vertices.array[3*this.next2]=c.x,this.vertices.array[3*this.next2+1]=c.y,this.vertices.array[3*this.next2+2]=c.z,this.vertices.needsUpdate=!0,this.next1=(this.next1+1)%this.keep,this.next2=this.next1+this.keep,this.count=Math.min(this.count+1,this.keep),this.geom.setDrawRange(this.next2-this.count,this.count)},decode64.S="ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/",decode64.e={};for(var i=0;i<64;i++)decode64.e[decode64.S.charAt(i)]=i;ROS3D.PointCloud2=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/points",this.points=new ROS3D.Points(a),this.rosTopic=void 0,this.subscribe()},ROS3D.PointCloud2.prototype.__proto__=THREE.Object3D.prototype,ROS3D.PointCloud2.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.PointCloud2.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"sensor_msgs/PointCloud2"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.PointCloud2.prototype.processMessage=function(a){if(this.points.setup(a.header.frame_id,a.point_step,a.fields)){var b,c=this.points.positionRatio;a.data.buffer?(this.points.buffer=a.data.buffer,b=a.height*a.width/c):(b=decode64(a.data,this.points.buffer,a.point_step,c),c=1);for(var d,e,f=new DataView(this.points.buffer.buffer),g=!a.is_bigendian,h=this.points.fields.x.offset,i=this.points.fields.y.offset,j=this.points.fields.z.offset,k=0;k0?(d=o[0].object,n.intersection=this.lastIntersection=o[0]):d=this.fallbackTarget,d!==this.lastTarget&&a.type.match(/mouse/)){var p=this.notify(d,"mouseover",n);0===p?this.notify(this.lastTarget,"mouseout",n):1===p&&(d=this.fallbackTarget)!==this.lastTarget&&(this.notify(d,"mouseover",n),this.notify(this.lastTarget,"mouseout",n))}if(d!==this.lastTarget&&a.type.match(/touch/)){this.notify(d,a.type,n)?(this.notify(this.lastTarget,"touchleave",n),this.notify(this.lastTarget,"touchend",n)):(d=this.fallbackTarget)!==this.lastTarget&&(this.notify(this.lastTarget,"touchmove",n),this.notify(this.lastTarget,"touchend",n))}this.notify(d,a.type,n),"mousedown"!==a.type&&"touchstart"!==a.type&&"touchmove"!==a.type||(this.dragging=!0),this.lastTarget=d},ROS3D.MouseHandler.prototype.notify=function(a,b,c){for(c.type=b,c.cancelBubble=!1,c.continueBubble=!1,c.stopPropagation=function(){c.cancelBubble=!0},c.continuePropagation=function(){c.continueBubble=!0},c.currentTarget=a;c.currentTarget;){if(c.currentTarget.dispatchEvent&&c.currentTarget.dispatchEvent instanceof Function){if(c.currentTarget.dispatchEvent(c),c.cancelBubble)return this.dispatchEvent(c),0;if(c.continueBubble)return 2}c.currentTarget=c.currentTarget.parent}return 1},Object.assign(ROS3D.MouseHandler.prototype,THREE.EventDispatcher.prototype),ROS3D.OrbitControls=function(a){function b(a){var b=a.domEvent;switch(b.preventDefault(),b.button){case 0:A=z.ROTATE,n.set(b.clientX,b.clientY);break;case 1:A=z.MOVE,u=new THREE.Vector3(0,0,1);var c=(new THREE.Matrix4).extractRotation(this.camera.matrix);u.applyMatrix4(c),t=j.center.clone(),v=j.camera.position.clone(),w=d(a.mouseRay,t,u);break;case 2:A=z.ZOOM,q.set(b.clientX,b.clientY)}this.showAxes()}function c(a){var b=a.domEvent;if(A===z.ROTATE)o.set(b.clientX,b.clientY),p.subVectors(o,n),j.rotateLeft(2*Math.PI*p.x/l*j.userRotateSpeed),j.rotateUp(2*Math.PI*p.y/l*j.userRotateSpeed),n.copy(o),this.showAxes();else if(A===z.ZOOM)r.set(b.clientX,b.clientY),s.subVectors(r,q),s.y>0?j.zoomIn():j.zoomOut(),q.copy(r),this.showAxes();else if(A===z.MOVE){var c=d(a.mouseRay,j.center,u);if(!c)return;var e=(new THREE.Vector3).subVectors(w.clone(),c.clone());j.center.addVectors(t.clone(),e.clone()),j.camera.position.addVectors(v.clone(),e.clone()),j.update(),j.camera.updateMatrixWorld(),this.showAxes()}}function d(a,b,c){var d=new THREE.Vector3;new THREE.Vector3;d.subVectors(b,a.origin);var e=a.direction.dot(c);if(Math.abs(e)0?j.zoomIn():j.zoomOut(),this.showAxes()}}function g(a){var b=a.domEvent;switch(b.touches.length){case 1:A=z.ROTATE,n.set(b.touches[0].pageX-window.scrollX,b.touches[0].pageY-window.scrollY);break;case 2:A=z.NONE,u=new THREE.Vector3(0,0,1);var c=(new THREE.Matrix4).extractRotation(this.camera.matrix);u.applyMatrix4(c),t=j.center.clone(),v=j.camera.position.clone(),w=d(a.mouseRay,t,u),x[0]=new THREE.Vector2(b.touches[0].pageX,b.touches[0].pageY),x[1]=new THREE.Vector2(b.touches[1].pageX,b.touches[1].pageY),y[0]=new THREE.Vector2(0,0),y[1]=new THREE.Vector2(0,0)}this.showAxes(),b.preventDefault()}function h(a){var b=a.domEvent;if(A===z.ROTATE)o.set(b.touches[0].pageX-window.scrollX,b.touches[0].pageY-window.scrollY),p.subVectors(o,n),j.rotateLeft(2*Math.PI*p.x/l*j.userRotateSpeed),j.rotateUp(2*Math.PI*p.y/l*j.userRotateSpeed),n.copy(o),this.showAxes();else{if(y[0].set(x[0].x-b.touches[0].pageX,x[0].y-b.touches[0].pageY),y[1].set(x[1].x-b.touches[1].pageX,x[1].y-b.touches[1].pageY),y[0].lengthSq()>m&&y[1].lengthSq()>m&&(x[0].set(b.touches[0].pageX,b.touches[0].pageY),x[1].set(b.touches[1].pageX,b.touches[1].pageY),y[0].dot(y[1])>0&&A!==z.ZOOM?A=z.MOVE:y[0].dot(y[1])<0&&A!==z.MOVE&&(A=z.ZOOM),A===z.ZOOM)){var c=new THREE.Vector2;c.subVectors(x[0],x[1]),y[0].dot(c)<0&&y[1].dot(c)>0?j.zoomOut():y[0].dot(c)>0&&y[1].dot(c)<0&&j.zoomIn()}if(A===z.MOVE){var e=d(a.mouseRay,j.center,u);if(!e)return;var f=(new THREE.Vector3).subVectors(w.clone(),e.clone());j.center.addVectors(t.clone(),f.clone()),j.camera.position.addVectors(v.clone(),f.clone()),j.update(),j.camera.updateMatrixWorld()}this.showAxes(),b.preventDefault()}}function i(a){var b=a.domEvent;1===b.touches.length&&A!==z.ROTATE?(A=z.ROTATE,n.set(b.touches[0].pageX-window.scrollX,b.touches[0].pageY-window.scrollY)):A=z.NONE}THREE.EventDispatcher.call(this);var j=this;a=a||{};var k=a.scene;this.camera=a.camera,this.center=new THREE.Vector3,this.userZoom=!0,this.userZoomSpeed=a.userZoomSpeed||1,this.userRotate=!0,this.userRotateSpeed=a.userRotateSpeed||1,this.autoRotate=a.autoRotate,this.autoRotateSpeed=a.autoRotateSpeed||2,this.camera.up=new THREE.Vector3(0,0,1);var l=1800,m=10,n=new THREE.Vector2,o=new THREE.Vector2,p=new THREE.Vector2,q=new THREE.Vector2,r=new THREE.Vector2,s=new THREE.Vector2,t=new THREE.Vector3,u=new THREE.Vector3,v=new THREE.Vector3,w=new THREE.Vector3,x=new Array(2),y=new Array(2);this.phiDelta=0,this.thetaDelta=0,this.scale=1,this.lastPosition=new THREE.Vector3;var z={NONE:-1,ROTATE:0,ZOOM:1,MOVE:2},A=z.NONE;this.axes=new ROS3D.Axes({shaftRadius:.025,headRadius:.07,headLength:.2}),k.add(this.axes),this.axes.traverse(function(a){a.visible=!1}),this.addEventListener("mousedown",b),this.addEventListener("mouseup",e),this.addEventListener("mousemove",c),this.addEventListener("touchstart",g),this.addEventListener("touchmove",h),this.addEventListener("touchend",i),this.addEventListener("mousewheel",f),this.addEventListener("DOMMouseScroll",f)},ROS3D.OrbitControls.prototype.showAxes=function(){var a=this;this.axes.traverse(function(a){a.visible=!0}),this.hideTimeout&&clearTimeout(this.hideTimeout),this.hideTimeout=setTimeout(function(){a.axes.traverse(function(a){a.visible=!1}),a.hideTimeout=!1},1e3)},ROS3D.OrbitControls.prototype.rotateLeft=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.thetaDelta-=a},ROS3D.OrbitControls.prototype.rotateRight=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.thetaDelta+=a},ROS3D.OrbitControls.prototype.rotateUp=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.phiDelta-=a},ROS3D.OrbitControls.prototype.rotateDown=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.phiDelta+=a},ROS3D.OrbitControls.prototype.zoomIn=function(a){void 0===a&&(a=Math.pow(.95,this.userZoomSpeed)),this.scale/=a},ROS3D.OrbitControls.prototype.zoomOut=function(a){void 0===a&&(a=Math.pow(.95,this.userZoomSpeed)),this.scale*=a},ROS3D.OrbitControls.prototype.update=function(){var a=this.camera.position,b=a.clone().sub(this.center),c=Math.atan2(b.y,b.x),d=Math.atan2(Math.sqrt(b.y*b.y+b.x*b.x),b.z);this.autoRotate&&this.rotateLeft(2*Math.PI/60/60*this.autoRotateSpeed),c+=this.thetaDelta,d+=this.phiDelta;d=Math.max(1e-6,Math.min(Math.PI-1e-6,d));var e=b.length();b.set(e*Math.sin(d)*Math.cos(c),e*Math.sin(d)*Math.sin(c),e*Math.cos(d)),b.multiplyScalar(this.scale),a.copy(this.center).add(b),this.camera.lookAt(this.center),e=b.length(),this.axes.position.copy(this.center),this.axes.scale.set(.05*e,.05*e,.05*e),this.axes.updateMatrixWorld(!0),this.thetaDelta=0,this.phiDelta=0,this.scale=1,this.lastPosition.distanceTo(this.camera.position)>0&&(this.dispatchEvent({type:"change"}),this.lastPosition.copy(this.camera.position))},Object.assign(ROS3D.OrbitControls.prototype,THREE.EventDispatcher.prototype),ROS3D.SceneNode=function(a){a=a||{};var b=this;this.tfClient=a.tfClient,this.frameID=a.frameID;var c=a.object;this.pose=a.pose||new ROSLIB.Pose,THREE.Object3D.call(this),this.visible=!1,this.add(c),this.updatePose(this.pose),this.tfUpdate=function(a){var c=new ROSLIB.Transform(a),d=new ROSLIB.Pose(b.pose);d.applyTransform(c),b.updatePose(d),b.visible=!0},this.tfClient.subscribe(this.frameID,this.tfUpdate)},ROS3D.SceneNode.prototype.__proto__=THREE.Object3D.prototype,ROS3D.SceneNode.prototype.updatePose=function(a){this.position.set(a.position.x,a.position.y,a.position.z),this.quaternion.set(a.orientation.x,a.orientation.y,a.orientation.z,a.orientation.w),this.updateMatrixWorld(!0)},ROS3D.SceneNode.prototype.unsubscribeTf=function(){this.tfClient.unsubscribe(this.frameID,this.tfUpdate)},ROS3D.Viewer=function(a){a=a||{};var b=a.divID,c=a.width,d=a.height,e=a.background||"#111111",f=a.antialias,g=a.intensity||.66,h=a.near||.01,i=a.far||1e3,j=a.alpha||1,k=a.cameraPose||{x:3,y:3,z:3},l=a.cameraZoomSpeed||.5;this.renderer=new THREE.WebGLRenderer({antialias:f,alpha:!0}),this.renderer.setClearColor(parseInt(e.replace("#","0x"),16),j),this.renderer.sortObjects=!1,this.renderer.setSize(c,d),this.renderer.shadowMap.enabled=!1,this.renderer.autoClear=!1,this.scene=new THREE.Scene,this.camera=new THREE.PerspectiveCamera(40,c/d,h,i),this.camera.position.x=k.x,this.camera.position.y=k.y,this.camera.position.z=k.z,this.cameraControls=new ROS3D.OrbitControls({scene:this.scene,camera:this.camera}),this.cameraControls.userZoomSpeed=l,this.scene.add(new THREE.AmbientLight(5592405)),this.directionalLight=new THREE.DirectionalLight(16777215,g),this.scene.add(this.directionalLight),this.selectableObjects=new THREE.Object3D,this.scene.add(this.selectableObjects);var m=new ROS3D.MouseHandler({renderer:this.renderer,camera:this.camera,rootObject:this.selectableObjects,fallbackTarget:this.cameraControls});this.highlighter=new ROS3D.Highlighter({mouseHandler:m}),this.stopped=!0,this.animationRequestId=void 0,document.getElementById(b).appendChild(this.renderer.domElement),this.start()},ROS3D.Viewer.prototype.start=function(){this.stopped=!1,this.draw()},ROS3D.Viewer.prototype.draw=function(){this.stopped||(this.cameraControls.update(),this.directionalLight.position=this.camera.localToWorld(new THREE.Vector3(-1,1,0)),this.directionalLight.position.normalize(),this.renderer.clear(!0,!0,!0),this.renderer.render(this.scene,this.camera),this.highlighter.renderHighlights(this.scene,this.renderer,this.camera),this.animationRequestId=requestAnimationFrame(this.draw.bind(this)))},ROS3D.Viewer.prototype.stop=function(){this.stopped||cancelAnimationFrame(this.animationRequestId),this.stopped=!0},ROS3D.Viewer.prototype.addObject=function(a,b){b?this.selectableObjects.add(a):this.scene.add(a)},ROS3D.Viewer.prototype.resize=function(a,b){this.camera.aspect=a/b,this.camera.updateProjectionMatrix(),this.renderer.setSize(a,b)}; \ No newline at end of file +;var _=new THREE.SpriteMaterial({map:$,useScreenCoordinates:!1}),aa=new THREE.Sprite(_),ba=c.scale.x;aa.scale.set(Z/W.height*ba,ba,1),this.add(aa)}break;case ROS3D.MARKER_MESH_RESOURCE:var ca=null;0===c.color.r&&0===c.color.g&&0===c.color.b&&0===c.color.a||(ca=d),this.msgMesh=c.mesh_resource.substr(10);var da=new ROS3D.MeshResource({path:b,resource:this.msgMesh,material:ca});this.add(da);break;case ROS3D.MARKER_TRIANGLE_LIST:var ea=new ROS3D.TriangleList({material:d,vertices:c.points,colors:c.colors});ea.scale.set(c.scale.x,c.scale.y,c.scale.z),this.add(ea);break;default:console.error("Currently unsupported marker type: "+c.type)}},ROS3D.Marker.prototype.__proto__=THREE.Object3D.prototype,ROS3D.Marker.prototype.setPose=function(a){this.position.x=a.position.x,this.position.y=a.position.y,this.position.z=a.position.z,this.quaternion.set(a.orientation.x,a.orientation.y,a.orientation.z,a.orientation.w),this.quaternion.normalize(),this.updateMatrixWorld()},ROS3D.Marker.prototype.update=function(a){if(this.setPose(a.pose),a.color.r!==this.msgColor.r||a.color.g!==this.msgColor.g||a.color.b!==this.msgColor.b||a.color.a!==this.msgColor.a){var b=ROS3D.makeColorMaterial(a.color.r,a.color.g,a.color.b,a.color.a);switch(a.type){case ROS3D.MARKER_LINE_STRIP:case ROS3D.MARKER_LINE_LIST:case ROS3D.MARKER_POINTS:break;case ROS3D.MARKER_ARROW:case ROS3D.MARKER_CUBE:case ROS3D.MARKER_SPHERE:case ROS3D.MARKER_CYLINDER:case ROS3D.MARKER_TRIANGLE_LIST:case ROS3D.MARKER_TEXT_VIEW_FACING:this.traverse(function(a){a instanceof THREE.Mesh&&(a.material=b)});break;case ROS3D.MARKER_MESH_RESOURCE:var c=null;0===a.color.r&&0===a.color.g&&0===a.color.b&&0===a.color.a||(c=this.colorMaterial),this.traverse(function(a){a instanceof THREE.Mesh&&(a.material=c)});break;case ROS3D.MARKER_CUBE_LIST:case ROS3D.MARKER_SPHERE_LIST:default:return!1}this.msgColor=a.color}var d=Math.abs(this.msgScale[0]-a.scale.x)>1e-6||Math.abs(this.msgScale[1]-a.scale.y)>1e-6||Math.abs(this.msgScale[2]-a.scale.z)>1e-6;switch(this.msgScale=[a.scale.x,a.scale.y,a.scale.z],a.type){case ROS3D.MARKER_CUBE:case ROS3D.MARKER_SPHERE:case ROS3D.MARKER_CYLINDER:if(d)return!1;break;case ROS3D.MARKER_TEXT_VIEW_FACING:if(d||this.text!==a.text)return!1;break;case ROS3D.MARKER_MESH_RESOURCE:if(a.mesh_resource.substr(10)!==this.msgMesh)return!1;if(d)return!1;break;case ROS3D.MARKER_ARROW:case ROS3D.MARKER_LINE_STRIP:case ROS3D.MARKER_LINE_LIST:case ROS3D.MARKER_CUBE_LIST:case ROS3D.MARKER_SPHERE_LIST:case ROS3D.MARKER_POINTS:case ROS3D.MARKER_TRIANGLE_LIST:return!1}return!0},ROS3D.Marker.prototype.dispose=function(){this.children.forEach(function(a){a instanceof ROS3D.MeshResource?a.children.forEach(function(b){void 0!==b.material&&b.material.dispose(),b.children.forEach(function(a){void 0!==a.geometry&&a.geometry.dispose(),void 0!==a.material&&a.material.dispose(),b.remove(a)}),a.remove(b)}):(void 0!==a.geometry&&a.geometry.dispose(),void 0!==a.material&&a.material.dispose()),a.parent.remove(a)})},ROS3D.MarkerArrayClient=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic,this.tfClient=a.tfClient,this.rootObject=a.rootObject||new THREE.Object3D,this.path=a.path||"/",this.markers={},this.rosTopic=void 0,this.subscribe()},ROS3D.MarkerArrayClient.prototype.__proto__=EventEmitter2.prototype,ROS3D.MarkerArrayClient.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"visualization_msgs/MarkerArray",compression:"png"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.MarkerArrayClient.prototype.processMessage=function(a){a.markers.forEach(function(a){if(0===a.action){var b=!1;if(a.ns+a.id in this.markers&&((b=this.markers[a.ns+a.id].children[0].update(a))||(this.markers[a.ns+a.id].unsubscribeTf(),this.rootObject.remove(this.markers[a.ns+a.id]))),!b){var c=new ROS3D.Marker({message:a,path:this.path});this.markers[a.ns+a.id]=new ROS3D.SceneNode({frameID:a.header.frame_id,tfClient:this.tfClient,object:c}),this.rootObject.add(this.markers[a.ns+a.id])}}else if(1===a.action)console.warn('Received marker message with deprecated action identifier "1"');else if(2===a.action)this.markers[a.ns+a.id].unsubscribeTf(),this.rootObject.remove(this.markers[a.ns+a.id]),delete this.markers[a.ns+a.id];else if(3===a.action){for(var d in this.markers)this.markers[d].unsubscribeTf(),this.rootObject.remove(this.markers[d]);this.markers={}}else console.warn('Received marker message with unknown action identifier "'+a.action+'"')}.bind(this)),this.emit("change")},ROS3D.MarkerArrayClient.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.MarkerClient=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic,this.tfClient=a.tfClient,this.rootObject=a.rootObject||new THREE.Object3D,this.path=a.path||"/",this.markers={},this.rosTopic=void 0,this.subscribe()},ROS3D.MarkerClient.prototype.__proto__=EventEmitter2.prototype,ROS3D.MarkerClient.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.MarkerClient.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"visualization_msgs/Marker",compression:"png"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.MarkerClient.prototype.processMessage=function(a){var b=new ROS3D.Marker({message:a,path:this.path}),c=this.markers[a.ns+a.id];c&&(c.unsubscribeTf(),this.rootObject.remove(c)),this.markers[a.ns+a.id]=new ROS3D.SceneNode({frameID:a.header.frame_id,tfClient:this.tfClient,object:b}),this.rootObject.add(this.markers[a.ns+a.id]),this.emit("change")},ROS3D.Arrow=function(a){a=a||{};var b=a.origin||new THREE.Vector3(0,0,0),c=a.direction||new THREE.Vector3(1,0,0),d=a.length||1,e=a.headLength||.2,f=a.shaftDiameter||.05,g=a.headDiameter||.1,h=a.material||new THREE.MeshBasicMaterial,i=d-e,j=new THREE.CylinderGeometry(.5*f,.5*f,i,12,1),k=new THREE.Matrix4;k.setPosition(new THREE.Vector3(0,.5*i,0)),j.applyMatrix(k);var l=new THREE.CylinderGeometry(0,.5*g,e,12,1);k.setPosition(new THREE.Vector3(0,i+.5*e,0)),l.applyMatrix(k),j.merge(l),THREE.Mesh.call(this,j,h),this.position.copy(b),this.setDirection(c)},ROS3D.Arrow.prototype.__proto__=THREE.Mesh.prototype,ROS3D.Arrow.prototype.setDirection=function(a){var b=new THREE.Vector3(0,1,0).cross(a),c=Math.acos(new THREE.Vector3(0,1,0).dot(a.clone().normalize()));this.matrix=(new THREE.Matrix4).makeRotationAxis(b.normalize(),c),this.rotation.setFromRotationMatrix(this.matrix,this.rotation.order)},ROS3D.Arrow.prototype.setLength=function(a){this.scale.set(a,a,a)},ROS3D.Arrow.prototype.setColor=function(a){this.material.color.setHex(a)},ROS3D.Arrow.prototype.dispose=function(){void 0!==this.geometry&&this.geometry.dispose(),void 0!==this.material&&this.material.dispose()},ROS3D.Arrow2=function(a){a=a||{};var b=a.origin||new THREE.Vector3(0,0,0),c=a.direction||new THREE.Vector3(1,0,0),d=a.length||1;a.headLength,a.shaftDiameter,a.headDiameter,a.material||new THREE.MeshBasicMaterial;THREE.ArrowHelper.call(this,c,b,d,16711680)},ROS3D.Arrow2.prototype.__proto__=THREE.ArrowHelper.prototype,ROS3D.Arrow2.prototype.dispose=function(){void 0!==this.line&&(this.line.material.dispose(),this.line.geometry.dispose()),void 0!==this.cone&&(this.cone.material.dispose(),this.cone.geometry.dispose())},ROS3D.Axes=function(a){function b(a){var b=new THREE.Color;b.setRGB(a.x,a.y,a.z);var d=new THREE.MeshBasicMaterial({color:b.getHex()}),e=new THREE.Vector3;e.crossVectors(a,new THREE.Vector3(0,-1,0));var f=new THREE.Quaternion;f.setFromAxisAngle(e,.5*Math.PI);var g=new THREE.Mesh(c.headGeom,d);g.position.copy(a),g.position.multiplyScalar(.95),g.quaternion.copy(f),g.updateMatrix(),c.add(g);var h=new THREE.Mesh(c.lineGeom,d);h.position.copy(a),h.position.multiplyScalar(.45),h.quaternion.copy(f),h.updateMatrix(),c.add(h)}var c=this;a=a||{};var d=a.shaftRadius||.008,e=a.headRadius||.023,f=a.headLength||.1;THREE.Object3D.call(this),this.lineGeom=new THREE.CylinderGeometry(d,d,1-f),this.headGeom=new THREE.CylinderGeometry(0,e,f),b(new THREE.Vector3(1,0,0)),b(new THREE.Vector3(0,1,0)),b(new THREE.Vector3(0,0,1))},ROS3D.Axes.prototype.__proto__=THREE.Object3D.prototype,ROS3D.Grid=function(a){a=a||{};var b=a.num_cells||10,c=a.color||"#cccccc",d=a.lineWidth||1,e=a.cellSize||1;THREE.Object3D.call(this);for(var f=new THREE.LineBasicMaterial({color:c,linewidth:d}),g=0;g<=b;++g){var h=e*b/2,i=h-g*e,j=new THREE.Geometry;j.vertices.push(new THREE.Vector3(-h,i,0),new THREE.Vector3(h,i,0));var k=new THREE.Geometry;k.vertices.push(new THREE.Vector3(i,-h,0),new THREE.Vector3(i,h,0)),this.add(new THREE.Line(j,f)),this.add(new THREE.Line(k,f))}},ROS3D.Grid.prototype.__proto__=THREE.Object3D.prototype,ROS3D.MeshResource=function(a){var b=this;a=a||{};var c=a.path||"/",d=a.resource,e=a.material||null;this.warnings=a.warnings,THREE.Object3D.call(this),"/"!==c.substr(c.length-1)&&(c+="/");var f,g=c+d,h=g.substr(-4).toLowerCase();".dae"===h?(f=new THREE.ColladaLoader,f.log=function(a){b.warnings&&console.warn(a)},f.load(g,function(a){null!==e&&a.scene.traverse(function(a){a instanceof THREE.Mesh&&void 0===a.material&&(a.material=e)}),b.add(a.scene)},null,function(a){console.error(a)})):".stl"===h&&(f=new THREE.STLLoader,f.load(g,function(a){a.computeFaceNormals();var c;c=null!==e?new THREE.Mesh(a,e):new THREE.Mesh(a,new THREE.MeshBasicMaterial({color:10066329})),b.add(c)},null,function(a){console.error(a)}))},ROS3D.MeshResource.prototype.__proto__=THREE.Object3D.prototype,ROS3D.TriangleList=function(a){a=a||{};var b=a.material||new THREE.MeshBasicMaterial,c=a.vertices,d=a.colors;THREE.Object3D.call(this),b.side=THREE.DoubleSide;var e=new THREE.Geometry;for(f=0;f=this.keep&&(this.sns[0].unsubscribeTf(),this.rootObject.remove(this.sns[0]),this.sns.shift()),this.options.origin=new THREE.Vector3(a.pose.pose.position.x,a.pose.pose.position.y,a.pose.pose.position.z);var b=new THREE.Quaternion(a.pose.pose.orientation.x,a.pose.pose.orientation.y,a.pose.pose.orientation.z,a.pose.pose.orientation.w);this.options.direction=new THREE.Vector3(1,0,0),this.options.direction.applyQuaternion(b),this.options.material=new THREE.MeshBasicMaterial({color:this.color});var c=new ROS3D.Arrow(this.options);this.sns.push(new ROS3D.SceneNode({frameID:a.header.frame_id,tfClient:this.tfClient,object:c})),this.rootObject.add(this.sns[this.sns.length-1])},ROS3D.Path=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/path",this.tfClient=a.tfClient,this.color=a.color||13369599,this.rootObject=a.rootObject||new THREE.Object3D,THREE.Object3D.call(this),this.sn=null,this.line=null,this.rosTopic=void 0,this.subscribe()},ROS3D.Path.prototype.__proto__=THREE.Object3D.prototype,ROS3D.Path.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.Path.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"nav_msgs/Path"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.Path.prototype.processMessage=function(a){null!==this.sn&&(this.sn.unsubscribeTf(),this.rootObject.remove(this.sn));for(var b=new THREE.Geometry,c=0;c=a.range_min&&e<=a.range_max){var f=a.angle_min+d*a.angle_increment;this.points.positions.array[c++]=e*Math.cos(f),this.points.positions.array[c++]=e*Math.sin(f),this.points.positions.array[c++]=0}}this.points.update(c/3)}},ROS3D.NavSatFix=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/gps/fix",this.rootObject=a.rootObject||new THREE.Object3D,this.object3d=a.object3d||new THREE.Object3D;var b=a.material||{};this.altitudeNaN=a.altitudeNaN||0,this.keep=a.keep||100,this.convert=a.convert||function(a,b,c){return new THREE.Vector3(a,b,c)},this.count=0,this.next1=0,this.next2=this.keep,this.geom=new THREE.BufferGeometry,this.vertices=new THREE.BufferAttribute(new Float32Array(6*this.keep),3),this.geom.addAttribute("position",this.vertices),this.material=b.isMaterial?b:new THREE.LineBasicMaterial(b),this.line=new THREE.Line(this.geom,this.material),this.rootObject.add(this.object3d),this.rootObject.add(this.line),this.rosTopic=void 0,this.subscribe()},ROS3D.NavSatFix.prototype.__proto__=THREE.Object3D.prototype,ROS3D.NavSatFix.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.NavSatFix.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"sensor_msgs/NavSatFix"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.NavSatFix.prototype.processMessage=function(a){var b=isNaN(a.altitude)?this.altitudeNaN:a.altitude,c=this.convert(a.longitude,a.latitude,b);this.object3d.position.copy(c),this.object3d.updateMatrixWorld(!0),this.vertices.array[3*this.next1]=c.x,this.vertices.array[3*this.next1+1]=c.y,this.vertices.array[3*this.next1+2]=c.z,this.vertices.array[3*this.next2]=c.x,this.vertices.array[3*this.next2+1]=c.y,this.vertices.array[3*this.next2+2]=c.z,this.vertices.needsUpdate=!0,this.next1=(this.next1+1)%this.keep,this.next2=this.next1+this.keep,this.count=Math.min(this.count+1,this.keep),this.geom.setDrawRange(this.next2-this.count,this.count)},decode64.S="ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/",decode64.e={};for(var i=0;i<64;i++)decode64.e[decode64.S.charAt(i)]=i;ROS3D.PointCloud2=function(a){a=a||{},this.ros=a.ros,this.topicName=a.topic||"/points",this.points=new ROS3D.Points(a),this.rosTopic=void 0,this.subscribe()},ROS3D.PointCloud2.prototype.__proto__=THREE.Object3D.prototype,ROS3D.PointCloud2.prototype.unsubscribe=function(){this.rosTopic&&this.rosTopic.unsubscribe()},ROS3D.PointCloud2.prototype.subscribe=function(){this.unsubscribe(),this.rosTopic=new ROSLIB.Topic({ros:this.ros,name:this.topicName,messageType:"sensor_msgs/PointCloud2"}),this.rosTopic.subscribe(this.processMessage.bind(this))},ROS3D.PointCloud2.prototype.processMessage=function(a){if(this.points.setup(a.header.frame_id,a.point_step,a.fields)){var b,c=this.points.pointRatio;a.data.buffer?(this.points.buffer=a.data.buffer,b=a.height*a.width/c):(b=decode64(a.data,this.points.buffer,a.point_step,c),c=1);for(var d,e,f=new DataView(this.points.buffer.buffer),g=!a.is_bigendian,h=this.points.fields.x.offset,i=this.points.fields.y.offset,j=this.points.fields.z.offset,k=0;k0?(d=o[0].object,n.intersection=this.lastIntersection=o[0]):d=this.fallbackTarget,d!==this.lastTarget&&a.type.match(/mouse/)){var p=this.notify(d,"mouseover",n);0===p?this.notify(this.lastTarget,"mouseout",n):1===p&&(d=this.fallbackTarget)!==this.lastTarget&&(this.notify(d,"mouseover",n),this.notify(this.lastTarget,"mouseout",n))}if(d!==this.lastTarget&&a.type.match(/touch/)){this.notify(d,a.type,n)?(this.notify(this.lastTarget,"touchleave",n),this.notify(this.lastTarget,"touchend",n)):(d=this.fallbackTarget)!==this.lastTarget&&(this.notify(this.lastTarget,"touchmove",n),this.notify(this.lastTarget,"touchend",n))}this.notify(d,a.type,n),"mousedown"!==a.type&&"touchstart"!==a.type&&"touchmove"!==a.type||(this.dragging=!0),this.lastTarget=d},ROS3D.MouseHandler.prototype.notify=function(a,b,c){for(c.type=b,c.cancelBubble=!1,c.continueBubble=!1,c.stopPropagation=function(){c.cancelBubble=!0},c.continuePropagation=function(){c.continueBubble=!0},c.currentTarget=a;c.currentTarget;){if(c.currentTarget.dispatchEvent&&c.currentTarget.dispatchEvent instanceof Function){if(c.currentTarget.dispatchEvent(c),c.cancelBubble)return this.dispatchEvent(c),0;if(c.continueBubble)return 2}c.currentTarget=c.currentTarget.parent}return 1},Object.assign(ROS3D.MouseHandler.prototype,THREE.EventDispatcher.prototype),ROS3D.OrbitControls=function(a){function b(a){var b=a.domEvent;switch(b.preventDefault(),b.button){case 0:A=z.ROTATE,n.set(b.clientX,b.clientY);break;case 1:A=z.MOVE,u=new THREE.Vector3(0,0,1);var c=(new THREE.Matrix4).extractRotation(this.camera.matrix);u.applyMatrix4(c),t=j.center.clone(),v=j.camera.position.clone(),w=d(a.mouseRay,t,u);break;case 2:A=z.ZOOM,q.set(b.clientX,b.clientY)}this.showAxes()}function c(a){var b=a.domEvent;if(A===z.ROTATE)o.set(b.clientX,b.clientY),p.subVectors(o,n),j.rotateLeft(2*Math.PI*p.x/l*j.userRotateSpeed),j.rotateUp(2*Math.PI*p.y/l*j.userRotateSpeed),n.copy(o),this.showAxes();else if(A===z.ZOOM)r.set(b.clientX,b.clientY),s.subVectors(r,q),s.y>0?j.zoomIn():j.zoomOut(),q.copy(r),this.showAxes();else if(A===z.MOVE){var c=d(a.mouseRay,j.center,u);if(!c)return;var e=(new THREE.Vector3).subVectors(w.clone(),c.clone());j.center.addVectors(t.clone(),e.clone()),j.camera.position.addVectors(v.clone(),e.clone()),j.update(),j.camera.updateMatrixWorld(),this.showAxes()}}function d(a,b,c){var d=new THREE.Vector3;new THREE.Vector3;d.subVectors(b,a.origin);var e=a.direction.dot(c);if(Math.abs(e)0?j.zoomIn():j.zoomOut(),this.showAxes()}}function g(a){var b=a.domEvent;switch(b.touches.length){case 1:A=z.ROTATE,n.set(b.touches[0].pageX-window.scrollX,b.touches[0].pageY-window.scrollY);break;case 2:A=z.NONE,u=new THREE.Vector3(0,0,1);var c=(new THREE.Matrix4).extractRotation(this.camera.matrix);u.applyMatrix4(c),t=j.center.clone(),v=j.camera.position.clone(),w=d(a.mouseRay,t,u),x[0]=new THREE.Vector2(b.touches[0].pageX,b.touches[0].pageY),x[1]=new THREE.Vector2(b.touches[1].pageX,b.touches[1].pageY),y[0]=new THREE.Vector2(0,0),y[1]=new THREE.Vector2(0,0)}this.showAxes(),b.preventDefault()}function h(a){var b=a.domEvent;if(A===z.ROTATE)o.set(b.touches[0].pageX-window.scrollX,b.touches[0].pageY-window.scrollY),p.subVectors(o,n),j.rotateLeft(2*Math.PI*p.x/l*j.userRotateSpeed),j.rotateUp(2*Math.PI*p.y/l*j.userRotateSpeed),n.copy(o),this.showAxes();else{if(y[0].set(x[0].x-b.touches[0].pageX,x[0].y-b.touches[0].pageY),y[1].set(x[1].x-b.touches[1].pageX,x[1].y-b.touches[1].pageY),y[0].lengthSq()>m&&y[1].lengthSq()>m&&(x[0].set(b.touches[0].pageX,b.touches[0].pageY),x[1].set(b.touches[1].pageX,b.touches[1].pageY),y[0].dot(y[1])>0&&A!==z.ZOOM?A=z.MOVE:y[0].dot(y[1])<0&&A!==z.MOVE&&(A=z.ZOOM),A===z.ZOOM)){var c=new THREE.Vector2;c.subVectors(x[0],x[1]),y[0].dot(c)<0&&y[1].dot(c)>0?j.zoomOut():y[0].dot(c)>0&&y[1].dot(c)<0&&j.zoomIn()}if(A===z.MOVE){var e=d(a.mouseRay,j.center,u);if(!e)return;var f=(new THREE.Vector3).subVectors(w.clone(),e.clone());j.center.addVectors(t.clone(),f.clone()),j.camera.position.addVectors(v.clone(),f.clone()),j.update(),j.camera.updateMatrixWorld()}this.showAxes(),b.preventDefault()}}function i(a){var b=a.domEvent;1===b.touches.length&&A!==z.ROTATE?(A=z.ROTATE,n.set(b.touches[0].pageX-window.scrollX,b.touches[0].pageY-window.scrollY)):A=z.NONE}THREE.EventDispatcher.call(this);var j=this;a=a||{};var k=a.scene;this.camera=a.camera,this.center=new THREE.Vector3,this.userZoom=!0,this.userZoomSpeed=a.userZoomSpeed||1,this.userRotate=!0,this.userRotateSpeed=a.userRotateSpeed||1,this.autoRotate=a.autoRotate,this.autoRotateSpeed=a.autoRotateSpeed||2,this.camera.up=new THREE.Vector3(0,0,1);var l=1800,m=10,n=new THREE.Vector2,o=new THREE.Vector2,p=new THREE.Vector2,q=new THREE.Vector2,r=new THREE.Vector2,s=new THREE.Vector2,t=new THREE.Vector3,u=new THREE.Vector3,v=new THREE.Vector3,w=new THREE.Vector3,x=new Array(2),y=new Array(2);this.phiDelta=0,this.thetaDelta=0,this.scale=1,this.lastPosition=new THREE.Vector3;var z={NONE:-1,ROTATE:0,ZOOM:1,MOVE:2},A=z.NONE;this.axes=new ROS3D.Axes({shaftRadius:.025,headRadius:.07,headLength:.2}),k.add(this.axes),this.axes.traverse(function(a){a.visible=!1}),this.addEventListener("mousedown",b),this.addEventListener("mouseup",e),this.addEventListener("mousemove",c),this.addEventListener("touchstart",g),this.addEventListener("touchmove",h),this.addEventListener("touchend",i),this.addEventListener("mousewheel",f),this.addEventListener("DOMMouseScroll",f)},ROS3D.OrbitControls.prototype.showAxes=function(){var a=this;this.axes.traverse(function(a){a.visible=!0}),this.hideTimeout&&clearTimeout(this.hideTimeout),this.hideTimeout=setTimeout(function(){a.axes.traverse(function(a){a.visible=!1}),a.hideTimeout=!1},1e3)},ROS3D.OrbitControls.prototype.rotateLeft=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.thetaDelta-=a},ROS3D.OrbitControls.prototype.rotateRight=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.thetaDelta+=a},ROS3D.OrbitControls.prototype.rotateUp=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.phiDelta-=a},ROS3D.OrbitControls.prototype.rotateDown=function(a){void 0===a&&(a=2*Math.PI/60/60*this.autoRotateSpeed),this.phiDelta+=a},ROS3D.OrbitControls.prototype.zoomIn=function(a){void 0===a&&(a=Math.pow(.95,this.userZoomSpeed)),this.scale/=a},ROS3D.OrbitControls.prototype.zoomOut=function(a){void 0===a&&(a=Math.pow(.95,this.userZoomSpeed)),this.scale*=a},ROS3D.OrbitControls.prototype.update=function(){var a=this.camera.position,b=a.clone().sub(this.center),c=Math.atan2(b.y,b.x),d=Math.atan2(Math.sqrt(b.y*b.y+b.x*b.x),b.z);this.autoRotate&&this.rotateLeft(2*Math.PI/60/60*this.autoRotateSpeed),c+=this.thetaDelta,d+=this.phiDelta;d=Math.max(1e-6,Math.min(Math.PI-1e-6,d));var e=b.length();b.set(e*Math.sin(d)*Math.cos(c),e*Math.sin(d)*Math.sin(c),e*Math.cos(d)),b.multiplyScalar(this.scale),a.copy(this.center).add(b),this.camera.lookAt(this.center),e=b.length(),this.axes.position.copy(this.center),this.axes.scale.set(.05*e,.05*e,.05*e),this.axes.updateMatrixWorld(!0),this.thetaDelta=0,this.phiDelta=0,this.scale=1,this.lastPosition.distanceTo(this.camera.position)>0&&(this.dispatchEvent({type:"change"}),this.lastPosition.copy(this.camera.position))},Object.assign(ROS3D.OrbitControls.prototype,THREE.EventDispatcher.prototype),ROS3D.SceneNode=function(a){a=a||{};var b=this;this.tfClient=a.tfClient,this.frameID=a.frameID;var c=a.object;this.pose=a.pose||new ROSLIB.Pose,THREE.Object3D.call(this),this.visible=!1,this.add(c),this.updatePose(this.pose),this.tfUpdate=function(a){var c=new ROSLIB.Transform(a),d=new ROSLIB.Pose(b.pose);d.applyTransform(c),b.updatePose(d),b.visible=!0},this.tfClient.subscribe(this.frameID,this.tfUpdate)},ROS3D.SceneNode.prototype.__proto__=THREE.Object3D.prototype,ROS3D.SceneNode.prototype.updatePose=function(a){this.position.set(a.position.x,a.position.y,a.position.z),this.quaternion.set(a.orientation.x,a.orientation.y,a.orientation.z,a.orientation.w),this.updateMatrixWorld(!0)},ROS3D.SceneNode.prototype.unsubscribeTf=function(){this.tfClient.unsubscribe(this.frameID,this.tfUpdate)},ROS3D.Viewer=function(a){a=a||{};var b=a.divID,c=a.width,d=a.height,e=a.background||"#111111",f=a.antialias,g=a.intensity||.66,h=a.near||.01,i=a.far||1e3,j=a.alpha||1,k=a.cameraPose||{x:3,y:3,z:3},l=a.cameraZoomSpeed||.5;this.renderer=new THREE.WebGLRenderer({antialias:f,alpha:!0}),this.renderer.setClearColor(parseInt(e.replace("#","0x"),16),j),this.renderer.sortObjects=!1,this.renderer.setSize(c,d),this.renderer.shadowMap.enabled=!1,this.renderer.autoClear=!1,this.scene=new THREE.Scene,this.camera=new THREE.PerspectiveCamera(40,c/d,h,i),this.camera.position.x=k.x,this.camera.position.y=k.y,this.camera.position.z=k.z,this.cameraControls=new ROS3D.OrbitControls({scene:this.scene,camera:this.camera}),this.cameraControls.userZoomSpeed=l,this.scene.add(new THREE.AmbientLight(5592405)),this.directionalLight=new THREE.DirectionalLight(16777215,g),this.scene.add(this.directionalLight),this.selectableObjects=new THREE.Object3D,this.scene.add(this.selectableObjects);var m=new ROS3D.MouseHandler({renderer:this.renderer,camera:this.camera,rootObject:this.selectableObjects,fallbackTarget:this.cameraControls});this.highlighter=new ROS3D.Highlighter({mouseHandler:m}),this.stopped=!0,this.animationRequestId=void 0,document.getElementById(b).appendChild(this.renderer.domElement),this.start()},ROS3D.Viewer.prototype.start=function(){this.stopped=!1,this.draw()},ROS3D.Viewer.prototype.draw=function(){this.stopped||(this.cameraControls.update(),this.directionalLight.position=this.camera.localToWorld(new THREE.Vector3(-1,1,0)),this.directionalLight.position.normalize(),this.renderer.clear(!0,!0,!0),this.renderer.render(this.scene,this.camera),this.highlighter.renderHighlights(this.scene,this.renderer,this.camera),this.animationRequestId=requestAnimationFrame(this.draw.bind(this)))},ROS3D.Viewer.prototype.stop=function(){this.stopped||cancelAnimationFrame(this.animationRequestId),this.stopped=!0},ROS3D.Viewer.prototype.addObject=function(a,b){b?this.selectableObjects.add(a):this.scene.add(a)},ROS3D.Viewer.prototype.resize=function(a,b){this.camera.aspect=a/b,this.camera.updateProjectionMatrix(),this.renderer.setSize(a,b)}; \ No newline at end of file diff --git a/src/sensors/LaserScan.js b/src/sensors/LaserScan.js index d8e0f53a..e2528463 100644 --- a/src/sensors/LaserScan.js +++ b/src/sensors/LaserScan.js @@ -53,7 +53,7 @@ ROS3D.LaserScan.prototype.processMessage = function(message){ } var n = message.ranges.length; var j = 0; - for(var i=0;i= message.range_min && range <= message.range_max){ var angle = message.angle_min + i * message.angle_increment; diff --git a/src/sensors/PointCloud2.js b/src/sensors/PointCloud2.js index 52c8679d..2959ed14 100644 --- a/src/sensors/PointCloud2.js +++ b/src/sensors/PointCloud2.js @@ -90,7 +90,7 @@ ROS3D.PointCloud2.prototype.processMessage = function(msg){ return; } - var n, pointRatio = this.points.positionRatio; + var n, pointRatio = this.points.pointRatio; if (msg.data.buffer) { this.points.buffer = msg.data.buffer;