-
Notifications
You must be signed in to change notification settings - Fork 215
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Update codebase to use Three.js version r88 #202
Merged
Merged
Changes from 12 commits
Commits
Show all changes
32 commits
Select commit
Hold shift + click to select a range
8e09982
fix dependencies. and bump patch
jihoonl 03bf58c
fix threejs
jihoonl fde6a14
Use [email protected]
e3cf789
Use object assign instead of apply. See mrdoob/three.js#8775
ff8698d
Rename CubeGeometry to BoxGeometry. Changed r65->r66
26f0cd8
Apply r66->r67
b261c28
r71->r72 Moved all shadowMap* properties in WebGLRenderer to shadowMa…
2c1270a
Apply mrdoob/three.js#8775, and use unproject from vector
7c78133
use project and unproject from vector object
7a35e01
deal with immutable objects r67->r68
58bb737
Update highlighting logic
d35a129
Update built modules
5adaece
Remove unused projector
5b6c1d6
update built module
49de6cf
Fix color material. But please check if #187 break
c4d1b86
update built module
b6341f2
Use copy in proper way
e5d99c2
Remove commented out old code
87df418
update built module
1439efb
bump bower version
44f5e34
Renameing variables in Highlighter
400c2e8
update built module
c727ac9
Add the forked verison of collada loader. See comments in the code wh…
6d4e87f
Assine material only if it is undefined
7e0c1a7
fix cdn to static
3d71d5d
set revision as develop
1d082a4
let Meshresource to use the forked collada loader
49b82d3
update built module
587c9ca
Add fixit comment
3a48e09
update built module
0ca58f6
Completely remove ColladaLoader2 from ROS3D. ColladaLoader2 no longer…
2f93d40
remove loader option
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -145,13 +145,11 @@ ROS3D.findClosestPoint = function(targetRay, mouseRay) { | |
* @returns the closest axis point | ||
*/ | ||
ROS3D.closestAxisPoint = function(axisRay, camera, mousePos) { | ||
var projector = new THREE.Projector(); | ||
|
||
// project axis onto screen | ||
var o = axisRay.origin.clone(); | ||
projector.projectVector(o, camera); | ||
o.project(camera); | ||
var o2 = axisRay.direction.clone().add(axisRay.origin); | ||
projector.projectVector(o2, camera); | ||
o2.project(camera); | ||
|
||
// d is the axis vector in screen space (d = o2-o) | ||
var d = o2.clone().sub(o); | ||
|
@@ -167,7 +165,7 @@ ROS3D.closestAxisPoint = function(axisRay, camera, mousePos) { | |
|
||
// go back to 3d by shooting a ray | ||
var vector = new THREE.Vector3(mp.x, mp.y, 0.5); | ||
projector.unprojectVector(vector, camera); | ||
vector.unproject(camera); | ||
var mpRay = new THREE.Ray(camera.position, vector.sub(camera.position).normalize()); | ||
|
||
return ROS3D.findClosestPoint(axisRay, mpRay); | ||
|
@@ -599,6 +597,7 @@ ROS3D.InteractiveMarker.prototype.moveAxis = function(control, origAxis, event3d | |
.multiplyScalar(t)); | ||
this.setPosition(control, p); | ||
|
||
|
||
event3d.stopPropagation(); | ||
} | ||
}; | ||
|
@@ -758,7 +757,7 @@ ROS3D.InteractiveMarker.prototype.buttonClick = function(control, event3d) { | |
* @param event3d - the event that caused this | ||
*/ | ||
ROS3D.InteractiveMarker.prototype.setPosition = function(control, position) { | ||
this.position = position; | ||
this.position.copy(position); | ||
this.feedbackEvent('user-pose-change', control); | ||
}; | ||
|
||
|
@@ -770,7 +769,7 @@ ROS3D.InteractiveMarker.prototype.setPosition = function(control, position) { | |
*/ | ||
ROS3D.InteractiveMarker.prototype.setOrientation = function(control, orientation) { | ||
orientation.normalize(); | ||
this.quaternion = orientation; | ||
this.quaternion.copy(orientation); | ||
this.feedbackEvent('user-pose-change', control); | ||
}; | ||
|
||
|
@@ -791,8 +790,8 @@ ROS3D.InteractiveMarker.prototype.onServerSetPose = function(event) { | |
this.position.y = pose.position.y; | ||
this.position.z = pose.position.z; | ||
|
||
this.quaternion = new THREE.Quaternion(pose.orientation.x, pose.orientation.y, | ||
pose.orientation.z, pose.orientation.w); | ||
this.quaternion.copy(new THREE.Quaternion(pose.orientation.x, pose.orientation.y, | ||
pose.orientation.z, pose.orientation.w)); | ||
|
||
this.updateMatrixWorld(true); | ||
} | ||
|
@@ -813,7 +812,8 @@ ROS3D.InteractiveMarker.prototype.dispose = function() { | |
}); | ||
}; | ||
|
||
THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarker.prototype ); | ||
// THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarker.prototype ); | ||
Object.assign(ROS3D.InteractiveMarker.prototype, THREE.EventDispatcher.prototype); | ||
|
||
/** | ||
* @author David Gossow - [email protected] | ||
|
@@ -1154,7 +1154,7 @@ ROS3D.InteractiveMarkerControl = function(options) { | |
break; | ||
case ROS3D.INTERACTIVE_MARKER_FIXED: | ||
this.updateMatrixWorld = function(force) { | ||
that.quaternion = that.parent.quaternion.clone().inverse(); | ||
that.quaternion.copy(that.parent.quaternion.clone().inverse()); | ||
that.updateMatrix(); | ||
that.matrixWorldNeedsUpdate = true; | ||
ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(that, force); | ||
|
@@ -1638,7 +1638,8 @@ ROS3D.InteractiveMarkerMenu.prototype.hide = function(event) { | |
document.body.removeChild(this.menuDomElem); | ||
}; | ||
|
||
THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarkerMenu.prototype ); | ||
// THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarkerMenu.prototype ); | ||
Object.assign(ROS3D.InteractiveMarkerMenu.prototype, THREE.EventDispatcher.prototype); | ||
|
||
/** | ||
* @author David Gossow - [email protected] | ||
|
@@ -1721,7 +1722,7 @@ ROS3D.Marker = function(options) { | |
break; | ||
case ROS3D.MARKER_CUBE: | ||
// set the cube dimensions | ||
var cubeGeom = new THREE.CubeGeometry(message.scale.x, message.scale.y, message.scale.z); | ||
var cubeGeom = new THREE.BoxGeometry(message.scale.x, message.scale.y, message.scale.z); | ||
this.add(new THREE.Mesh(cubeGeom, colorMaterial)); | ||
break; | ||
case ROS3D.MARKER_SPHERE: | ||
|
@@ -1738,7 +1739,7 @@ ROS3D.Marker = function(options) { | |
var cylinderGeom = new THREE.CylinderGeometry(0.5, 0.5, 1, 16, 1, false); | ||
var cylinderMesh = new THREE.Mesh(cylinderGeom, colorMaterial); | ||
cylinderMesh.quaternion.setFromAxisAngle(new THREE.Vector3(1, 0, 0), Math.PI * 0.5); | ||
cylinderMesh.scale = new THREE.Vector3(message.scale.x, message.scale.z, message.scale.y); | ||
cylinderMesh.scale.set(message.scale.x, message.scale.z, message.scale.y); | ||
this.add(cylinderMesh); | ||
break; | ||
case ROS3D.MARKER_LINE_STRIP: | ||
|
@@ -1816,7 +1817,7 @@ ROS3D.Marker = function(options) { | |
// add the points | ||
var p, cube, curColor, newMesh; | ||
for (p = 0; p < numPoints; p+=stepSize) { | ||
cube = new THREE.CubeGeometry(message.scale.x, message.scale.y, message.scale.z); | ||
cube = new THREE.BoxGeometry(message.scale.x, message.scale.y, message.scale.z); | ||
|
||
// check the color | ||
if(createColors) { | ||
|
@@ -1966,7 +1967,7 @@ ROS3D.Marker = function(options) { | |
vertices : message.points, | ||
colors : message.colors | ||
}); | ||
tri.scale = new THREE.Vector3(message.scale.x, message.scale.y, message.scale.z); | ||
tri.scale.set(message.scale.x, message.scale.y, message.scale.z); | ||
this.add(tri); | ||
break; | ||
default: | ||
|
@@ -1988,7 +1989,7 @@ ROS3D.Marker.prototype.setPose = function(pose) { | |
this.position.z = pose.position.z; | ||
|
||
// set the rotation | ||
this.quaternion = new THREE.Quaternion(pose.orientation.x, pose.orientation.y, | ||
this.quaternion.set(pose.orientation.x, pose.orientation.y, | ||
pose.orientation.z, pose.orientation.w); | ||
this.quaternion.normalize(); | ||
|
||
|
@@ -2366,11 +2367,12 @@ ROS3D.Arrow = function(options) { | |
coneGeometry.applyMatrix(m); | ||
|
||
// put the arrow together | ||
THREE.GeometryUtils.merge(geometry, coneGeometry); | ||
// DEPRECATED: THREE.GeometryUtils.merge(geometry, coneGeometry); | ||
geometry.merge(coneGeometry); | ||
|
||
THREE.Mesh.call(this, geometry, material); | ||
|
||
this.position = origin; | ||
this.position.copy(origin); | ||
this.setDirection(direction); | ||
}; | ||
ROS3D.Arrow.prototype.__proto__ = THREE.Mesh.prototype; | ||
|
@@ -2532,17 +2534,17 @@ ROS3D.Axes = function(options) { | |
|
||
// create the arrow | ||
var arrow = new THREE.Mesh(that.headGeom, material); | ||
arrow.position = axis.clone(); | ||
arrow.position.copy(axis); | ||
arrow.position.multiplyScalar(0.95); | ||
arrow.quaternion = rot; | ||
arrow.quaternion.copy(rot); | ||
arrow.updateMatrix(); | ||
that.add(arrow); | ||
|
||
// create the line | ||
var line = new THREE.Mesh(that.lineGeom, material); | ||
line.position = axis.clone(); | ||
line.position.copy(axis); | ||
line.position.multiplyScalar(0.45); | ||
line.quaternion = rot; | ||
line.quaternion.copy(rot); | ||
line.updateMatrix(); | ||
that.add(line); | ||
} | ||
|
@@ -2658,7 +2660,7 @@ ROS3D.MeshResource = function(options) { | |
// check for a scale factor in ColladaLoader2 | ||
if(loaderType === ROS3D.COLLADA_LOADER_2 && collada.dae.asset.unit) { | ||
var scale = collada.dae.asset.unit; | ||
collada.scene.scale = new THREE.Vector3(scale, scale, scale); | ||
collada.scene.scale.set(scale, scale, scale); | ||
} | ||
|
||
// add a texture to anything that is missing one | ||
|
@@ -2758,7 +2760,6 @@ ROS3D.TriangleList = function(options) { | |
|
||
geometry.computeBoundingBox(); | ||
geometry.computeBoundingSphere(); | ||
geometry.computeCentroids(); | ||
geometry.computeFaceNormals(); | ||
|
||
this.add(new THREE.Mesh(geometry, material)); | ||
|
@@ -3909,11 +3910,7 @@ ROS3D.Urdf = function(options) { | |
|
||
// check for a scale | ||
if(link.visuals[i].geometry.scale) { | ||
mesh.scale = new THREE.Vector3( | ||
visual.geometry.scale.x, | ||
visual.geometry.scale.y, | ||
visual.geometry.scale.z | ||
); | ||
mesh.scale.copy(visual.geometry.scale); | ||
} | ||
|
||
// create a scene node with the model | ||
|
@@ -3936,7 +3933,7 @@ ROS3D.Urdf = function(options) { | |
switch (visual.geometry.type) { | ||
case ROSLIB.URDF_BOX: | ||
var dimension = visual.geometry.dimension; | ||
var cube = new THREE.CubeGeometry(dimension.x, dimension.y, dimension.z); | ||
var cube = new THREE.BoxGeometry(dimension.x, dimension.y, dimension.z); | ||
shapeMesh = new THREE.Mesh(cube, colorMaterial); | ||
break; | ||
case ROSLIB.URDF_CYLINDER: | ||
|
@@ -4059,7 +4056,8 @@ ROS3D.Highlighter = function(options) { | |
* @param event - the event that contains the target of the mouseover | ||
*/ | ||
ROS3D.Highlighter.prototype.onMouseOver = function(event) { | ||
this.hoverObjs.push(event.currentTarget); | ||
// this.hoverObjs.push(event.currentTarget); | ||
this.highlightObject(event.currentTarget, true); | ||
}; | ||
|
||
/** | ||
|
@@ -4068,64 +4066,45 @@ ROS3D.Highlighter.prototype.onMouseOver = function(event) { | |
* @param event - the event that contains the target of the mouseout | ||
*/ | ||
ROS3D.Highlighter.prototype.onMouseOut = function(event) { | ||
this.hoverObjs.splice(this.hoverObjs.indexOf(event.currentTarget), 1); | ||
// this.hoverObjs.splice(this.hoverObjs.indexOf(event.currentTarget), 1); | ||
this.highlightObject(event.currentTarget, false); | ||
}; | ||
|
||
|
||
/** | ||
* Add all corresponding webgl objects in the given scene and add them to the given render list. | ||
* Highlight and unhighlight the given object | ||
* | ||
* @param scene - the scene to check for webgl objects | ||
* @param objects - the objects list to check | ||
* @param renderList - the list to add to | ||
*/ | ||
ROS3D.Highlighter.prototype.getWebglObjects = function(scene, objects, renderList) { | ||
var objlist = scene.__webglObjects; | ||
// get corresponding webgl objects | ||
for ( var c = 0; c < objects.length; c++) { | ||
if (objects[c]) { | ||
for ( var o = objlist.length - 1; o >= 0; o--) { | ||
if (objlist[o].object === objects[c]) { | ||
renderList.push(objlist[o]); | ||
break; | ||
} | ||
* @param object - the target object to (un)highlight | ||
* @param flag - whether to highlight or unhighlight | ||
*/ | ||
ROS3D.Highlighter.prototype.highlightObject = function (object, flag) { | ||
if(object.material === undefined) { | ||
if(object.children === undefined) { | ||
return; | ||
} | ||
else { | ||
for(var c = 0 ; c < object.children.length; c++) { | ||
this.highlightObject(object.children[c], flag); | ||
} | ||
// recurse into children | ||
this.getWebglObjects(scene, objects[c].children, renderList); | ||
} | ||
} | ||
}; | ||
|
||
/** | ||
* Render highlighted objects in the scene. | ||
* | ||
* @param renderer - the renderer to use | ||
* @param scene - the scene to use | ||
* @param camera - the camera to use | ||
*/ | ||
ROS3D.Highlighter.prototype.renderHighlight = function(renderer, scene, camera) { | ||
// get webgl objects | ||
var renderList = []; | ||
this.getWebglObjects(scene, this.hoverObjs, renderList); | ||
|
||
// define highlight material | ||
scene.overrideMaterial = new THREE.MeshBasicMaterial({ | ||
fog : false, | ||
opacity : 0.5, | ||
depthTest : true, | ||
depthWrite : false, | ||
polygonOffset : true, | ||
polygonOffsetUnits : -1, | ||
side : THREE.DoubleSide | ||
}); | ||
|
||
// swap render lists, render, undo | ||
var oldWebglObjects = scene.__webglObjects; | ||
scene.__webglObjects = renderList; | ||
|
||
renderer.render(scene, camera); | ||
|
||
scene.__webglObjects = oldWebglObjects; | ||
scene.overrideMaterial = null; | ||
else { | ||
if(flag) { | ||
object.currentMaterial = object.material; | ||
object.material = new THREE.MeshBasicMaterial({ | ||
fog : false, | ||
opacity : 0.5, | ||
depthTest : true, | ||
depthWrite : false, | ||
polygonOffset : true, | ||
polygonOffsetUnits : -1, | ||
side : THREE.DoubleSide | ||
}); | ||
} | ||
else { | ||
object.material = object.currentMaterial; | ||
} | ||
} | ||
}; | ||
|
||
/** | ||
|
@@ -4199,7 +4178,8 @@ ROS3D.MouseHandler.prototype.processDomEvent = function(domEvent) { | |
var deviceX = left / target.clientWidth * 2 - 1; | ||
var deviceY = -top / target.clientHeight * 2 + 1; | ||
var vector = new THREE.Vector3(deviceX, deviceY, 0.5); | ||
this.projector.unprojectVector(vector, this.camera); | ||
// DEPRECATED: this.projector.unprojectVector(vector, this.camera); | ||
vector.unproject(this.camera); | ||
// use the THREE raycaster | ||
var mouseRaycaster = new THREE.Raycaster(this.camera.position.clone(), vector.sub( | ||
this.camera.position).normalize()); | ||
|
@@ -4351,7 +4331,8 @@ ROS3D.MouseHandler.prototype.notify = function(target, type, event3D) { | |
return 1; // Event Failed | ||
}; | ||
|
||
THREE.EventDispatcher.prototype.apply( ROS3D.MouseHandler.prototype ); | ||
// THREE.EventDispatcher.prototype.apply( ROS3D.MouseHandler.prototype ); | ||
Object.assign(ROS3D.MouseHandler.prototype, THREE.EventDispatcher.prototype); | ||
|
||
/** | ||
* @author David Gossow - [email protected] | ||
|
@@ -4830,18 +4811,20 @@ ROS3D.OrbitControls.prototype.update = function() { | |
phi = Math.max(eps, Math.min(Math.PI - eps, phi)); | ||
|
||
var radius = offset.length(); | ||
offset.y = radius * Math.sin(phi) * Math.sin(theta); | ||
offset.z = radius * Math.cos(phi); | ||
offset.x = radius * Math.sin(phi) * Math.cos(theta); | ||
offset.set( | ||
radius * Math.sin(phi) * Math.cos(theta), | ||
radius * Math.sin(phi) * Math.sin(theta), | ||
radius * Math.cos(phi) | ||
); | ||
offset.multiplyScalar(this.scale); | ||
|
||
position.copy(this.center).add(offset); | ||
|
||
this.camera.lookAt(this.center); | ||
|
||
radius = offset.length(); | ||
this.axes.position = this.center.clone(); | ||
this.axes.scale.x = this.axes.scale.y = this.axes.scale.z = radius * 0.05; | ||
this.axes.position.copy(this.center); | ||
this.axes.scale.set(radius * 0.05, radius * 0.05, radius * 0.05); | ||
this.axes.updateMatrixWorld(true); | ||
|
||
this.thetaDelta = 0; | ||
|
@@ -4856,7 +4839,8 @@ ROS3D.OrbitControls.prototype.update = function() { | |
} | ||
}; | ||
|
||
THREE.EventDispatcher.prototype.apply( ROS3D.OrbitControls.prototype ); | ||
// THREE.EventDispatcher.prototype.apply( ROS3D.OrbitControls.prototype ); | ||
Object.assign(ROS3D.OrbitControls.prototype, THREE.EventDispatcher.prototype); | ||
|
||
/** | ||
* @author Jihoon Lee - [email protected] | ||
|
@@ -4973,7 +4957,7 @@ ROS3D.Viewer = function(options) { | |
this.renderer.setClearColor(parseInt(background.replace('#', '0x'), 16), alpha); | ||
this.renderer.sortObjects = false; | ||
this.renderer.setSize(width, height); | ||
this.renderer.shadowMapEnabled = false; | ||
this.renderer.shadowMap.enabled = false; | ||
this.renderer.autoClear = false; | ||
|
||
// create the global scene | ||
|
@@ -5049,9 +5033,6 @@ ROS3D.Viewer.prototype.draw = function(){ | |
this.renderer.clear(true, true, true); | ||
this.renderer.render(this.scene, this.camera); | ||
|
||
// render any mouseovers | ||
this.highlighter.renderHighlight(this.renderer, this.scene, this.camera); | ||
|
||
// draw the frame | ||
this.animationRequestId = requestAnimationFrame(this.draw.bind(this)); | ||
}; | ||
|
Large diffs are not rendered by default.
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
you could probably use set() here, as you did with the other quaternions further down