Skip to content

Commit

Permalink
Merge pull request #44 from rctoris/devel
Browse files Browse the repository at this point in the history
MARKER_CUBE_LIST added to Marker.js
  • Loading branch information
rctoris committed Jun 5, 2013
2 parents 2f305a7 + a8bff36 commit 6051c23
Show file tree
Hide file tree
Showing 5 changed files with 103 additions and 60 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
DEVEL - **r6**
* MARKER_CUBE_LIST added to Marker.js [(rctoris)](https://github.com/rctoris/)

2013-05-29 - **r5**
* Added DepthCloud class for point ploud streaming with ros_web_video and depthcloud_encoder ([jkammerl](https://github.com/jkammerl/), [dgossow](https://github.com/dgossow/))
Expand Down
79 changes: 50 additions & 29 deletions build/ros3d.js
Original file line number Diff line number Diff line change
Expand Up @@ -177,28 +177,25 @@ ROS3D.closestAxisPoint = function(axisRay, camera, mousePos) {
*
* @constructor
* @param options - object with following keys:
* * f - The camera's focal length
* * pointSize - Point size (pixels) for rendered point cloud
* * width, height - Dimensions of the video stream
* * whiteness - Blends rgb values to white (0..100)
* * varianceThreshold - Threshold for variance filter, used for compression artifact removal
* * url - the URL of the stream
* * 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 video stream
* * height (optional) - height of the video stream
* * whiteness (optional) - blends rgb values to white (0..100)
* * varianceThreshold (optional) - threshold for variance filter, used for compression artifact removal
*/
ROS3D.DepthCloud = function(options) {

options = options || {};
THREE.Object3D.call(this);

// ///////////////////////////
// depth cloud options
// ///////////////////////////


this.url = options.url;
// f defaults to standard Kinect calibration
this.f = (options.f !== undefined) ? options.f : 526;
this.pointSize = (options.pointSize !== undefined) ? options.pointSize : 3;
this.width = (options.width !== undefined) ? options.width : 1024;
this.height = (options.height !== undefined) ? options.height : 1024;
this.whiteness = (options.whiteness !== undefined) ? options.whiteness : 0;
this.varianceThreshold = (options.varianceThreshold !== undefined) ? options.varianceThreshold : 0.000016667;
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.video = document.createElement('video');
Expand All @@ -210,9 +207,7 @@ ROS3D.DepthCloud = function(options) {
this.video.crossOrigin = 'Anonymous';
this.video.setAttribute('crossorigin', 'Anonymous');

// ///////////////////////////
// load shaders
// ///////////////////////////
// define custom shaders
this.vertex_shader = [
'uniform sampler2D map;',
'',
Expand Down Expand Up @@ -385,15 +380,15 @@ ROS3D.DepthCloud = function(options) {
};
ROS3D.DepthCloud.prototype.__proto__ = THREE.Object3D.prototype;

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

/*
/**
* Callback called when video metadata is ready
*/
ROS3D.DepthCloud.prototype.initStreamer = function() {
Expand All @@ -412,9 +407,7 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
}

this.material = new THREE.ShaderMaterial({

uniforms : {

'map' : {
type : 't',
value : this.texture
Expand Down Expand Up @@ -450,8 +443,6 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
},
vertexShader : this.vertex_shader,
fragmentShader : this.fragment_shader
// depthWrite: false

});

this.mesh = new THREE.ParticleSystem(this.geometry, this.material);
Expand All @@ -469,14 +460,14 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
}
};

/*
/**
* Start video playback
*/
ROS3D.DepthCloud.prototype.startStream = function() {
this.video.play();
};

/*
/**
* Stop video playback
*/
ROS3D.DepthCloud.prototype.stopStream = function() {
Expand Down Expand Up @@ -1726,6 +1717,36 @@ ROS3D.Marker = function(options) {
this.add(cylinderMesh);
break;
case ROS3D.MARKER_CUBE_LIST:
// holds the main object
var object = new THREE.Object3D();

// check if custom colors should be used
var numPoints = message.points.length;
var createColors = (numPoints === message.colors.length);
// do not render giant lists
var stepSize = Math.ceil(numPoints / 1250);

// 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);

// check the color
if(createColors) {
curColor = ROS3D.makeColorMaterial(message.colors[p].r, message.colors[p].g, message.colors[p].b, message.colors[p].a);
} else {
curColor = colorMaterial;
}

newMesh = new THREE.Mesh(cube, curColor);
newMesh.position.x = message.points[p].x;
newMesh.position.y = message.points[p].y;
newMesh.position.z = message.points[p].z;
object.add(newMesh);
}

this.add(object);
break;
case ROS3D.MARKER_SPHERE_LIST:
case ROS3D.MARKER_POINTS:
// for now, use a particle system for the lists
Expand Down
4 changes: 2 additions & 2 deletions build/ros3d.min.js

Large diffs are not rendered by default.

49 changes: 20 additions & 29 deletions src/depthcloud/DepthCloud.js
Original file line number Diff line number Diff line change
Expand Up @@ -7,28 +7,25 @@
*
* @constructor
* @param options - object with following keys:
* * f - The camera's focal length
* * pointSize - Point size (pixels) for rendered point cloud
* * width, height - Dimensions of the video stream
* * whiteness - Blends rgb values to white (0..100)
* * varianceThreshold - Threshold for variance filter, used for compression artifact removal
* * url - the URL of the stream
* * 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 video stream
* * height (optional) - height of the video stream
* * whiteness (optional) - blends rgb values to white (0..100)
* * varianceThreshold (optional) - threshold for variance filter, used for compression artifact removal
*/
ROS3D.DepthCloud = function(options) {

options = options || {};
THREE.Object3D.call(this);

// ///////////////////////////
// depth cloud options
// ///////////////////////////


this.url = options.url;
// f defaults to standard Kinect calibration
this.f = (options.f !== undefined) ? options.f : 526;
this.pointSize = (options.pointSize !== undefined) ? options.pointSize : 3;
this.width = (options.width !== undefined) ? options.width : 1024;
this.height = (options.height !== undefined) ? options.height : 1024;
this.whiteness = (options.whiteness !== undefined) ? options.whiteness : 0;
this.varianceThreshold = (options.varianceThreshold !== undefined) ? options.varianceThreshold : 0.000016667;
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.video = document.createElement('video');
Expand All @@ -40,9 +37,7 @@ ROS3D.DepthCloud = function(options) {
this.video.crossOrigin = 'Anonymous';
this.video.setAttribute('crossorigin', 'Anonymous');

// ///////////////////////////
// load shaders
// ///////////////////////////
// define custom shaders
this.vertex_shader = [
'uniform sampler2D map;',
'',
Expand Down Expand Up @@ -215,15 +210,15 @@ ROS3D.DepthCloud = function(options) {
};
ROS3D.DepthCloud.prototype.__proto__ = THREE.Object3D.prototype;

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

/*
/**
* Callback called when video metadata is ready
*/
ROS3D.DepthCloud.prototype.initStreamer = function() {
Expand All @@ -242,9 +237,7 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
}

this.material = new THREE.ShaderMaterial({

uniforms : {

'map' : {
type : 't',
value : this.texture
Expand Down Expand Up @@ -280,8 +273,6 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
},
vertexShader : this.vertex_shader,
fragmentShader : this.fragment_shader
// depthWrite: false

});

this.mesh = new THREE.ParticleSystem(this.geometry, this.material);
Expand All @@ -299,14 +290,14 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
}
};

/*
/**
* Start video playback
*/
ROS3D.DepthCloud.prototype.startStream = function() {
this.video.play();
};

/*
/**
* Stop video playback
*/
ROS3D.DepthCloud.prototype.stopStream = function() {
Expand Down
30 changes: 30 additions & 0 deletions src/markers/Marker.js
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,36 @@ ROS3D.Marker = function(options) {
this.add(cylinderMesh);
break;
case ROS3D.MARKER_CUBE_LIST:
// holds the main object
var object = new THREE.Object3D();

// check if custom colors should be used
var numPoints = message.points.length;
var createColors = (numPoints === message.colors.length);
// do not render giant lists
var stepSize = Math.ceil(numPoints / 1250);

// 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);

// check the color
if(createColors) {
curColor = ROS3D.makeColorMaterial(message.colors[p].r, message.colors[p].g, message.colors[p].b, message.colors[p].a);
} else {
curColor = colorMaterial;
}

newMesh = new THREE.Mesh(cube, curColor);
newMesh.position.x = message.points[p].x;
newMesh.position.y = message.points[p].y;
newMesh.position.z = message.points[p].z;
object.add(newMesh);
}

this.add(object);
break;
case ROS3D.MARKER_SPHERE_LIST:
case ROS3D.MARKER_POINTS:
// for now, use a particle system for the lists
Expand Down

0 comments on commit 6051c23

Please sign in to comment.