Skip to content
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

Feature/closecloud adjustments #1

Open
wants to merge 37 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
37 commits
Select commit Hold shift + click to select a range
2a45373
ros3djs: improvements to Axes and SceneNode
Feb 10, 2015
8f0a86c
markers: limit the subscription queue length
Feb 11, 2015
71c23db
ros3djs: updates to zoom settings
b1willaert Feb 13, 2015
bce7918
ros3djs: make object optional for SceneNode (may be set lateron)
Mar 6, 2015
285d69e
markers: do trimming of leading slashes in frameID
b1willaert Mar 18, 2015
c1f063e
markers: make clients more robust in processing markers
psoetens Jan 4, 2016
5734e39
upgrade to THREE r70
Mar 3, 2015
7867fc8
depthcloud: Introduce 2 new point cloud visualisation classes
psoetens Jan 4, 2016
1abffd8
fix indentation: grunt complains
Jan 6, 2016
91c1830
PointCloud ByteBuffer dependency comment
Jan 6, 2016
760fcb3
MarkerArrayClient: add removeArray method
Jan 6, 2016
0448b86
grunt build --force (to ignore missing dependency)
Jan 6, 2016
e964203
Merge remote-tracking branch 'upstream/develop' into feature/closeclo…
Jan 6, 2016
1f074ca
CloseCloud: add mjpeg stream type feature
Jan 6, 2016
2f88449
remove trailing whitespace + grunt build --force
Jan 6, 2016
5d26463
Merge branch 'develop' into feature/closecloud_adjustments
Mar 10, 2016
1ce9312
Merge branch 'develop' into feature/closecloud_adjustments
Jan 17, 2017
2c73084
Pointcloud improvements
Jan 18, 2017
52c8aca
SceneNode: use prototype's transformPose to update transforms from th…
Jan 23, 2017
ef03267
Merge branch 'develop' into feature/closecloud_adjustments
Feb 1, 2017
c8dd9ee
Viewer: add ability to directly pass canvas
Feb 8, 2017
83abd25
MarkerArrayClient: free memory by resetting MarkerArray when removeArray
Feb 8, 2017
392db69
Merge branch 'develop' into feature/closecloud_adjustments
Feb 17, 2017
fded35d
MarkerArrayClient: unsubscribe before removing marker
Feb 22, 2017
8088f0c
Don't auto-increment provided alpha value in makeColorMaterial by 10%
Feb 22, 2017
e0df355
Adjust THREE.Projector for THREEr70
Jun 8, 2017
d5be424
PointCloud: add opacity/transparency option for material
Jun 8, 2017
cf98ab9
Make demos link in README point to the demos page
Feb 21, 2017
f9956b5
Added mocha and chai packages to setup for in browser testing
faizanv Apr 10, 2017
b060af2
Added tests for Arrow and Grid
faizanv Apr 10, 2017
e03a529
Fixed typo in README
faizanv Apr 10, 2017
1c96e1b
Added linting to test files
faizanv Apr 21, 2017
cc041ac
Removed extra mocha.css file
faizanv Apr 21, 2017
7bb7d33
PointCloud: use BufferGeometry instead of Geometry
Jun 19, 2017
31106ae
Add BufferView helper class for reading point data
Jul 11, 2017
c95b2ac
Merge branch 'develop' into feature/closecloud_adjustments
Jul 26, 2017
9b3cf77
Merge branch 'develop' into feature/closecloud_adjustments
Aug 22, 2017
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
716 changes: 645 additions & 71 deletions build/ros3d.js

Large diffs are not rendered by default.

6 changes: 3 additions & 3 deletions build/ros3d.min.js

Large diffs are not rendered by default.

8 changes: 4 additions & 4 deletions src/Ros3D.js
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ ROS3D.makeColorMaterial = function(r, g, b, a) {
if (a <= 0.99) {
return new THREE.MeshBasicMaterial({
color : color.getHex(),
opacity : a + 0.1,
opacity : a,
transparent : true,
depthWrite : true,
blendSrc : THREE.SrcAlphaFactor,
Expand Down Expand Up @@ -149,9 +149,9 @@ ROS3D.closestAxisPoint = function(axisRay, camera, mousePos) {

// 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);
Expand All @@ -167,7 +167,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);
Expand Down
336 changes: 336 additions & 0 deletions src/depthcloud/CloseCloud.js
Original file line number Diff line number Diff line change
@@ -0,0 +1,336 @@
/**
* @author Julius Kammerl - [email protected]
*/

/**
* The CloseCloud object. An alternative DepthCloud implementation which
* has higher resolution when the depth range is less than 2m.
*
* @constructor
* @param options - object with following keys:
*
* * url - the URL of the stream
* * streamType (optional) - the stream type: mjpeg or vp8 video (defaults to vp8)
* * f (optional) - the camera's focal length (defaults to standard Kinect calibration)
* * pointSize (optional) - point size (pixels) for rendered point cloud
* * width (optional) - width of the depthcloud encoded video stream
* * height (optional) - height of the depthcloud encoded video stream
* * whiteness (optional) - blends rgb values to white (0..100)
* * varianceThreshold (optional) - threshold for variance filter, used for compression artifact removal
*/
ROS3D.CloseCloud = function(options) {
THREE.Object3D.call(this);
this.type = 'CloseCloud';

this.options = options || {};
this.url = options.url;
this.streamType = options.streamType || 'vp8';
this.f = options.f || 526;
this.pointSize = options.pointSize || 3;
this.width = options.width || 1024;
this.height = options.height || 1024;
this.whiteness = options.whiteness || 0;
this.varianceThreshold = options.varianceThreshold || 0.000016667;

var metaLoaded = false;

this.isMjpeg = this.streamType.toLowerCase() === 'mjpeg';

this.video = document.createElement(this.isMjpeg ? 'img' : 'video');
this.video.width = this.width;
this.video.height = this.height;
this.video.addEventListener(this.isMjpeg ? 'load' : 'loadedmetadata', this.metaLoaded.bind(this), false);

if (!this.isMjpeg) {
this.video.loop = true;
}

this.video.src = this.url;
this.video.crossOrigin = 'Anonymous';
this.video.setAttribute('crossorigin', 'Anonymous');

// define custom shaders
this.vertex_shader = [
'uniform sampler2D map;',
'',
'uniform float width;',
'uniform float height;',
'',
'uniform float pointSize;',
'uniform float zOffset;',
'',
'uniform float focallength;',
'',
'varying vec2 vUvP;',
'varying vec2 colorP;',
'',
'varying float depthVariance;',
'varying float maskVal;',
'',
'float sampleDepth(vec2 pos)',
' {',
' float depth;',
' ',
' vec2 vUv = vec2( pos.x / (width*2.0), pos.y / (height*2.0)+0.5 );',
' vec2 vUv2 = vec2( pos.x / (width*2.0)+0.5, pos.y / (height*2.0)+0.5 );',
' ',
' vec4 depthColor = texture2D( map, vUv );',
' ',
' depth = ( depthColor.r + depthColor.g + depthColor.b ) / 3.0;',
' ',
' if (depth > (1.0 - 3.0/255.0) )', // If we're closer than 3 values from saturation, check the next depth image
' {',
' vec4 depthColor2 = texture2D( map, vUv2 );',
' float depth2 = ( depthColor2.r + depthColor2.g + depthColor2.b ) / 3.0 ;',
' depth += depth2;',
' }',
' ',
' return depth;',
' }',
'',
'float median(float a, float b, float c)',
' {',
' float r=a;',
' ',
' if ( (a<b) && (b<c) )',
' {',
' r = b;',
' }',
' if ( (a<c) && (c<b) )',
' {',
' r = c;',
' }',
' return r;',
' }',
'',
'float variance(float d1, float d2, float d3, float d4, float d5, float d6, float d7, float d8, float d9)',
' {',
' float mean = (d1 + d2 + d3 + d4 + d5 + d6 + d7 + d8 + d9) / 9.0;',
' float t1 = (d1-mean);',
' float t2 = (d2-mean);',
' float t3 = (d3-mean);',
' float t4 = (d4-mean);',
' float t5 = (d5-mean);',
' float t6 = (d6-mean);',
' float t7 = (d7-mean);',
' float t8 = (d8-mean);',
' float t9 = (d9-mean);',
' float v = (t1*t1+t2*t2+t3*t3+t4*t4+t5*t5+t6*t6+t7*t7+t8*t8+t9*t9)/9.0;',
' return v;',
' }',
'',
'vec2 decodeDepth(vec2 pos)',
' {',
' vec2 ret;',
' ',
' ',
' float depth1 = sampleDepth(vec2(position.x-1.0, position.y-1.0));',
' float depth2 = sampleDepth(vec2(position.x, position.y-1.0));',
' float depth3 = sampleDepth(vec2(position.x+1.0, position.y-1.0));',
' float depth4 = sampleDepth(vec2(position.x-1.0, position.y));',
' float depth5 = sampleDepth(vec2(position.x, position.y));',
' float depth6 = sampleDepth(vec2(position.x+1.0, position.y));',
' float depth7 = sampleDepth(vec2(position.x-1.0, position.y+1.0));',
' float depth8 = sampleDepth(vec2(position.x, position.y+1.0));',
' float depth9 = sampleDepth(vec2(position.x+1.0, position.y+1.0));',
' ',
' float median1 = median(depth1, depth2, depth3);',
' float median2 = median(depth4, depth5, depth6);',
' float median3 = median(depth7, depth8, depth9);',
' ',
' ret.x = median(median1, median2, median3);',
' ret.y = variance(depth1, depth2, depth3, depth4, depth5, depth6, depth7, depth8, depth9);',
' ',
' return ret;',
' ',
' }',
'',
'',
'void main() {',
' ',
' vUvP = vec2( position.x / (width*2.0), position.y / (height*2.0)+0.5 );',
' colorP = vec2( position.x / (width*2.0)+0.5 , position.y / (height*2.0) );',
' ',
' vec4 pos = vec4(0.0,0.0,0.0,0.0);',
' depthVariance = 0.0;',
' ',
' if ( (vUvP.x<0.0)|| (vUvP.x>0.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 * (1000.0/focallength) * -1.0,',
' ( position.y / height - 0.5 ) * z *0.5 * (1000.0/focallength),',
' (- z + zOffset / 1000.0) * 1.0,',
' 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.CloseCloud.prototype = Object.create( THREE.Object3D.prototype );
ROS3D.CloseCloud.prototype.constructor = ROS3D.CloseCloud;

ROS3D.CloseCloud.prototype.clone = function ( object, recursive ) {

if ( object === undefined ) { object = new ROS3D.CloseCloud( this.options ); }

THREE.Object3D.prototype.clone.call( this, object, recursive );

return object;

};

/**
* Callback called when video metadata is ready
*/
ROS3D.CloseCloud.prototype.metaLoaded = function() {
this.metaLoaded = true;
this.initStreamer();
};

/**
* Callback called when video metadata is ready
*/
ROS3D.CloseCloud.prototype.initStreamer = function() {

if (this.metaLoaded) {
this.dctexture = new THREE.Texture(this.video);
this.dcgeometry = new THREE.Geometry();

var qwidth = this.width / 2;
var qheight = this.height / 2;
// the number of points is a forth of the total image size
for (var i = 0, l = qwidth * qheight; i < l; i++) {

var vertex = new THREE.Vector3();
vertex.x = (i % qwidth);
vertex.y = Math.floor(i / qwidth);

this.dcgeometry.vertices.push(vertex);
}

this.dcmaterial = new THREE.ShaderMaterial({
uniforms : {
'map' : {
type : 't',
value : this.dctexture
},
'width' : {
type : 'f',
value : qwidth
},
'height' : {
type : 'f',
value : qheight
},
'focallength' : {
type : 'f',
value : this.f
},
'pointSize' : {
type : 'f',
value : this.pointSize
},
'zOffset' : {
type : 'f',
value : 0
},
'whiteness' : {
type : 'f',
value : this.whiteness
},
'varianceThreshold' : {
type : 'f',
value : this.varianceThreshold
}
},
vertexShader : this.vertex_shader,
fragmentShader : this.fragment_shader
});
this.dcmaterial.color = new THREE.Color( 0xffffff );
this.mesh = new THREE.PointCloud(this.dcgeometry, this.dcmaterial);
this.mesh.frustumCulled = false;
this.mesh.position.set(0,0,0);

this.add(this.mesh);

var that = this;
this.interval = setInterval(function() {
if (that.isMjpeg || that.video.readyState === that.video.HAVE_ENOUGH_DATA) {
that.dctexture.needsUpdate = true;
}
}, 1000 / 30);
}
};

/**
* Start video playback
*/
ROS3D.CloseCloud.prototype.startStream = function() {
if (!this.isMjpeg) {
this.video.play();
}
};

/**
* Stop video playback
*/
ROS3D.CloseCloud.prototype.stopStream = function() {
if (!this.isMjpeg) {
this.video.pause();
}
this.video.src = ''; // forcefully silence the video streaming url.
clearInterval(this.interval);
};
2 changes: 1 addition & 1 deletion src/depthcloud/DepthCloud.js
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,7 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
fragmentShader : this.fragment_shader
});

this.mesh = new THREE.ParticleSystem(this.geometry, this.material);
this.mesh = new THREE.PointCloud(this.geometry, this.material);
this.mesh.position.x = 0;
this.mesh.position.y = 0;
this.add(this.mesh);
Expand Down
Loading