diff --git a/examples/continuousmap.html b/examples/continuousmap.html index bc81d8d5..e48612d4 100644 --- a/examples/continuousmap.html +++ b/examples/continuousmap.html @@ -3,7 +3,7 @@
- + diff --git a/examples/depthcloud.html b/examples/depthcloud.html index 7764c021..95e8a1ba 100644 --- a/examples/depthcloud.html +++ b/examples/depthcloud.html @@ -3,7 +3,7 @@ - + diff --git a/examples/interactivemarkers.html b/examples/interactivemarkers.html index d3aa7983..e3071b4a 100644 --- a/examples/interactivemarkers.html +++ b/examples/interactivemarkers.html @@ -3,7 +3,7 @@ - + diff --git a/examples/kitti.html b/examples/kitti.html index 0ed42ab9..6deeddc2 100644 --- a/examples/kitti.html +++ b/examples/kitti.html @@ -3,7 +3,7 @@ - + diff --git a/examples/map.html b/examples/map.html index 87a3cf8c..6bc5a8d5 100644 --- a/examples/map.html +++ b/examples/map.html @@ -3,7 +3,7 @@ - + diff --git a/examples/markers.html b/examples/markers.html index 6f63852e..b2c67b87 100644 --- a/examples/markers.html +++ b/examples/markers.html @@ -3,7 +3,7 @@ - + diff --git a/examples/navsatfix.html b/examples/navsatfix.html index 7ca885e1..0e4648ce 100644 --- a/examples/navsatfix.html +++ b/examples/navsatfix.html @@ -3,7 +3,7 @@ - + diff --git a/examples/octree.html b/examples/octree.html index da931234..53016c13 100644 --- a/examples/octree.html +++ b/examples/octree.html @@ -3,7 +3,7 @@ - + diff --git a/examples/pointcloud2.html b/examples/pointcloud2.html index ed0caa46..b4caf8e3 100644 --- a/examples/pointcloud2.html +++ b/examples/pointcloud2.html @@ -3,7 +3,7 @@ - + diff --git a/examples/urdf.html b/examples/urdf.html index 18c3167f..abb03813 100644 --- a/examples/urdf.html +++ b/examples/urdf.html @@ -3,7 +3,7 @@ - + diff --git a/package-lock.json b/package-lock.json index 485f8eca..d373b848 100644 --- a/package-lock.json +++ b/package-lock.json @@ -11,7 +11,7 @@ "dependencies": { "eventemitter2": "^6.4.0", "roslib": "^1.0.0", - "three": "^0.89.0" + "three": "~0.120.0" }, "devDependencies": { "@rollup/plugin-buble": "^1.0.0", @@ -7403,9 +7403,9 @@ "dev": true }, "node_modules/three": { - "version": "0.89.0", - "resolved": "https://registry.npmjs.org/three/-/three-0.89.0.tgz", - "integrity": "sha1-RELYGaYWiHG40ss3rRKiQxDBcPU=" + "version": "0.120.1", + "resolved": "https://registry.npmjs.org/three/-/three-0.120.1.tgz", + "integrity": "sha512-ktaCRFUR7JUZcKec+cBRz+oBex5pOVaJhrtxvFF2T7on53o9UkEux+/Nh1g/4zeb4t/pbxIFcADbn/ACu3LC1g==" }, "node_modules/through": { "version": "2.3.8", @@ -14009,9 +14009,9 @@ "dev": true }, "three": { - "version": "0.89.0", - "resolved": "https://registry.npmjs.org/three/-/three-0.89.0.tgz", - "integrity": "sha1-RELYGaYWiHG40ss3rRKiQxDBcPU=" + "version": "0.120.1", + "resolved": "https://registry.npmjs.org/three/-/three-0.120.1.tgz", + "integrity": "sha512-ktaCRFUR7JUZcKec+cBRz+oBex5pOVaJhrtxvFF2T7on53o9UkEux+/Nh1g/4zeb4t/pbxIFcADbn/ACu3LC1g==" }, "through": { "version": "2.3.8", diff --git a/package.json b/package.json index 6a79c284..6c69c263 100644 --- a/package.json +++ b/package.json @@ -9,7 +9,7 @@ "dependencies": { "eventemitter2": "^6.4.0", "roslib": "^1.0.0", - "three": "^0.89.0" + "three": "~0.120.0" }, "devDependencies": { "@rollup/plugin-buble": "^1.0.0", diff --git a/src/interactivemarkers/InteractiveMarker.js b/src/interactivemarkers/InteractiveMarker.js index f4e4f821..d4f3ba95 100644 --- a/src/interactivemarkers/InteractiveMarker.js +++ b/src/interactivemarkers/InteractiveMarker.js @@ -212,7 +212,7 @@ ROS3D.InteractiveMarker.prototype.rotateAxis = function(control, origOrientation // rotates from world to plane coords var orientationWorld = this.dragStart.orientationWorld.clone().multiply(orientation); - var orientationWorldInv = orientationWorld.clone().inverse(); + var orientationWorldInv = orientationWorld.clone().invert(); // rotate original and current intersection into local coords intersection.sub(rotOrigin); diff --git a/src/interactivemarkers/InteractiveMarkerControl.js b/src/interactivemarkers/InteractiveMarkerControl.js index 2af0daea..7f467694 100644 --- a/src/interactivemarkers/InteractiveMarkerControl.js +++ b/src/interactivemarkers/InteractiveMarkerControl.js @@ -138,7 +138,7 @@ ROS3D.InteractiveMarkerControl = function(options) { var posInv = this.parent.position.clone().multiplyScalar(-1); switch (message.orientation_mode) { case ROS3D.INTERACTIVE_MARKER_INHERIT: - rotInv = this.parent.quaternion.clone().inverse(); + rotInv = this.parent.quaternion.clone().invert(); break; case ROS3D.INTERACTIVE_MARKER_FIXED: break; @@ -231,7 +231,7 @@ ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld = function (force) { that.currentControlOri.normalize(); break; case ROS3D.INTERACTIVE_MARKER_FIXED: - that.quaternion.copy(that.parent.quaternion.clone().inverse()); + that.quaternion.copy(that.parent.quaternion.clone().invert()); that.updateMatrix(); that.matrixWorldNeedsUpdate = true; ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(that, force); @@ -247,7 +247,7 @@ ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld = function (force) { ros2Gl.makeRotationFromEuler(rv); var worldToLocal = new THREE.Matrix4(); - worldToLocal.getInverse(that.parent.matrixWorld); + worldToLocal.copy(that.parent.matrixWorld).invert(); cameraRot.multiplyMatrices(cameraRot, ros2Gl); cameraRot.multiplyMatrices(worldToLocal, cameraRot); diff --git a/src/models/Arrow.js b/src/models/Arrow.js index 9714ca0a..f12e2004 100644 --- a/src/models/Arrow.js +++ b/src/models/Arrow.js @@ -34,12 +34,12 @@ ROS3D.Arrow = function(options) { 12, 1); var m = new THREE.Matrix4(); m.setPosition(new THREE.Vector3(0, shaftLength * 0.5, 0)); - geometry.applyMatrix(m); + geometry.applyMatrix4(m); // create the head var coneGeometry = new THREE.CylinderGeometry(0, headDiameter * 0.5, headLength, 12, 1); m.setPosition(new THREE.Vector3(0, shaftLength + (headLength * 0.5), 0)); - coneGeometry.applyMatrix(m); + coneGeometry.applyMatrix4(m); // put the arrow together geometry.merge(coneGeometry); diff --git a/src/models/TriangleList.js b/src/models/TriangleList.js index c2138f88..557e0569 100644 --- a/src/models/TriangleList.js +++ b/src/models/TriangleList.js @@ -43,7 +43,7 @@ ROS3D.TriangleList = function(options) { } geometry.faces.push(faceVert); } - material.vertexColors = THREE.VertexColors; + material.vertexColors = true; } else if (colors.length === vertices.length / 3) { // use per-triangle color for (i = 0; i < vertices.length; i += 3) { @@ -51,7 +51,7 @@ ROS3D.TriangleList = function(options) { faceTri.color.setRGB(colors[i / 3].r, colors[i / 3].g, colors[i / 3].b); geometry.faces.push(faceTri); } - material.vertexColors = THREE.FaceColors; + material.vertexColors = true; } else { // use marker color for (i = 0; i < vertices.length; i += 3) { diff --git a/src/navigation/OcTreeBase.js b/src/navigation/OcTreeBase.js index ac4c77cf..2a77d388 100644 --- a/src/navigation/OcTreeBase.js +++ b/src/navigation/OcTreeBase.js @@ -403,14 +403,14 @@ ROS3D.OcTreeBase.prototype.buildGeometry = function () { const material = new THREE.MeshBasicMaterial({ color: 'white', flatShading: true, - vertexColors: THREE.VertexColors, + vertexColors: true, transparent: this.opacity < 1.0, opacity: this.opacity }); - geometry.addAttribute('position', new THREE.BufferAttribute(new Float32Array(vertices), 3)); - geometry.addAttribute('normal', new THREE.BufferAttribute(new Float32Array(normals), 3)); - geometry.addAttribute('color', new THREE.BufferAttribute(new Float32Array(colors), 3)); + geometry.setAttribute('position', new THREE.BufferAttribute(new Float32Array(vertices), 3)); + geometry.setAttribute('normal', new THREE.BufferAttribute(new Float32Array(normals), 3)); + geometry.setAttribute('color', new THREE.BufferAttribute(new Float32Array(colors), 3)); geometry.setIndex(indices); diff --git a/src/navigation/Path.js b/src/navigation/Path.js index 2b26d0d0..29c535a1 100644 --- a/src/navigation/Path.js +++ b/src/navigation/Path.js @@ -66,9 +66,9 @@ ROS3D.Path.prototype.processMessage = function(message){ lineGeometry.vertices.push(v3); } - lineGeometry.computeLineDistances(); var lineMaterial = new THREE.LineBasicMaterial( { color: this.color } ); var line = new THREE.Line( lineGeometry, lineMaterial ); + // line.computeLineDistances(); // Only needed for LineDashedMaterial this.sn = new ROS3D.SceneNode({ frameID : message.header.frame_id, diff --git a/src/navigation/Polygon.js b/src/navigation/Polygon.js index 9c36edb1..6cdf8225 100644 --- a/src/navigation/Polygon.js +++ b/src/navigation/Polygon.js @@ -69,9 +69,11 @@ ROS3D.Polygon.prototype.processMessage = function(message){ v3 = new THREE.Vector3( message.polygon.points[0].x, message.polygon.points[0].y, message.polygon.points[0].z); lineGeometry.vertices.push(v3); - lineGeometry.computeLineDistances(); + var lineMaterial = new THREE.LineBasicMaterial( { color: this.color } ); var line = new THREE.Line( lineGeometry, lineMaterial ); + line.computeLineDistances(); + // line.computeLineDistances(); // Only needed for LineDashedMaterial this.sn = new ROS3D.SceneNode({ frameID : message.header.frame_id, diff --git a/src/navigation/PoseArray.js b/src/navigation/PoseArray.js index 1f5e7c47..952eca81 100644 --- a/src/navigation/PoseArray.js +++ b/src/navigation/PoseArray.js @@ -84,10 +84,9 @@ ROS3D.PoseArray.prototype.processMessage = function(message){ lineGeometry.vertices.push(side1.add(v3)); lineGeometry.vertices.push(side2.add(v3)); lineGeometry.vertices.push(tip); - - lineGeometry.computeLineDistances(); var lineMaterial = new THREE.LineBasicMaterial( { color: this.color } ); line = new THREE.Line( lineGeometry, lineMaterial ); + // line.computeLineDistances(); // Only needed for LineDashedMaterial group.add(line); } diff --git a/src/sensors/NavSatFix.js b/src/sensors/NavSatFix.js index 97be4741..ddb8f42d 100644 --- a/src/sensors/NavSatFix.js +++ b/src/sensors/NavSatFix.js @@ -37,7 +37,7 @@ ROS3D.NavSatFix = function(options) { this.geom = new THREE.BufferGeometry(); this.vertices = new THREE.BufferAttribute(new Float32Array( 6 * this.keep ), 3 ); - this.geom.addAttribute( 'position', this.vertices); + this.geom.setAttribute('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); diff --git a/src/sensors/Points.js b/src/sensors/Points.js index 36648c6e..eae70a89 100644 --- a/src/sensors/Points.js +++ b/src/sensors/Points.js @@ -57,7 +57,7 @@ ROS3D.Points.prototype.setup = function(frame, point_step, fields) this.geom = new THREE.BufferGeometry(); this.positions = new THREE.BufferAttribute( new Float32Array( this.max_pts * 3), 3, false ); - this.geom.addAttribute( 'position', this.positions.setDynamic(true) ); + this.geom.setAttribute('position', this.positions.setDynamic(true) ); if(!this.colorsrc && this.fields.rgb) { this.colorsrc = 'rgb'; @@ -66,7 +66,7 @@ ROS3D.Points.prototype.setup = function(frame, point_step, fields) var field = this.fields[this.colorsrc]; if (field) { this.colors = new THREE.BufferAttribute( new Float32Array( this.max_pts * 3), 3, false ); - this.geom.addAttribute( 'color', this.colors.setDynamic(true) ); + this.geom.setAttribute('color', this.colors.setDynamic(true) ); var offset = field.offset; this.getColor = [ function(dv,base,le){return dv.getInt8(base+offset,le);}, @@ -86,7 +86,7 @@ ROS3D.Points.prototype.setup = function(frame, point_step, fields) if(!this.material.isMaterial) { // if it is an option, apply defaults and pass it to a PointsMaterial if(this.colors && this.material.vertexColors === undefined) { - this.material.vertexColors = THREE.VertexColors; + this.material.vertexColors = true; } this.material = new THREE.PointsMaterial(this.material); } diff --git a/src/visualization/SceneNode.js b/src/visualization/SceneNode.js index 253e5f38..ac5d9937 100644 --- a/src/visualization/SceneNode.js +++ b/src/visualization/SceneNode.js @@ -25,6 +25,7 @@ ROS3D.SceneNode = function(options) { // Do not render this object until we receive a TF update this.visible = false; + this.layers.disable(0); // add the model this.add(object); @@ -43,6 +44,7 @@ ROS3D.SceneNode = function(options) { // update the world this.updatePose(poseTransformed); this.visible = true; + this.layers.enable(0); }; // listen for TF updates diff --git a/src/visualization/interaction/Highlighter.js b/src/visualization/interaction/Highlighter.js index 44541529..781f14f8 100644 --- a/src/visualization/interaction/Highlighter.js +++ b/src/visualization/interaction/Highlighter.js @@ -97,6 +97,7 @@ ROS3D.Highlighter.prototype.makeEverythingInvisible = function (scene) { || currentObject instanceof THREE.Sprite ) { currentObject.previousVisibility = currentObject.visible; currentObject.visible = false; + currentObject.layers.disable(0); // Invisible } }); }; @@ -113,6 +114,7 @@ ROS3D.Highlighter.prototype.makeHighlightedVisible = function (scene) { if ( currentObject instanceof THREE.Mesh || currentObject instanceof THREE.Line || currentObject instanceof THREE.Sprite ) { currentObject.visible = true; + currentObject.layers.enable(0); // Visible } }; @@ -120,6 +122,7 @@ ROS3D.Highlighter.prototype.makeHighlightedVisible = function (scene) { var selectedObject = this.hoverObjs[uuid]; // Make each selected object and all of its children visible selectedObject.visible = true; + selectedObject.layers.enable(0); // Visible selectedObject.traverse(makeVisible); } }; @@ -134,6 +137,11 @@ ROS3D.Highlighter.prototype.restoreVisibility = function (scene) { scene.traverse(function(currentObject) { if (currentObject.hasOwnProperty('previousVisibility')) { currentObject.visible = currentObject.previousVisibility; + if (currentObject.visible) { + currentObject.layers.enable(0); // Visible + } else { + currentObject.layers.disable(0); // Invisible + } } }.bind(this)); }; diff --git a/src/visualization/interaction/MouseHandler.js b/src/visualization/interaction/MouseHandler.js index 94a85e81..e5f3c729 100644 --- a/src/visualization/interaction/MouseHandler.js +++ b/src/visualization/interaction/MouseHandler.js @@ -71,7 +71,7 @@ ROS3D.MouseHandler.prototype.processDomEvent = function(domEvent) { var mousePos = new THREE.Vector2(deviceX, deviceY); var mouseRaycaster = new THREE.Raycaster(); - mouseRaycaster.linePrecision = 0.001; + mouseRaycaster.params.Line.threshold = 0.001; mouseRaycaster.setFromCamera(mousePos, this.camera); var mouseRay = mouseRaycaster.ray; diff --git a/src/visualization/interaction/OrbitControls.js b/src/visualization/interaction/OrbitControls.js index 1c8e0720..d1b11300 100644 --- a/src/visualization/interaction/OrbitControls.js +++ b/src/visualization/interaction/OrbitControls.js @@ -81,6 +81,7 @@ ROS3D.OrbitControls = function(options) { scene.add(this.axes); this.axes.traverse(function(obj) { obj.visible = false; + obj.layers.disable(0); // Invisible }); } @@ -376,6 +377,7 @@ ROS3D.OrbitControls.prototype.showAxes = function() { this.axes.traverse(function(obj) { obj.visible = true; + obj.layers.enable(0); // Visible }); if (this.hideTimeout) { clearTimeout(this.hideTimeout); @@ -383,6 +385,7 @@ ROS3D.OrbitControls.prototype.showAxes = function() { this.hideTimeout = setTimeout(function() { that.axes.traverse(function(obj) { obj.visible = false; + obj.layers.disable(0); // Invisible }); that.hideTimeout = false; }, 1000);