Skip to content

Commit

Permalink
Merge 'RobotWebTools/develop' into 'keego/ES5_WITH_TRANSPILER'
Browse files Browse the repository at this point in the history
- This pulls in changes from PRs RobotWebTools#207, RobotWebTools#210, RobotWebTools#218, RobotWebTools#221, and RobotWebTools#223
- Note: src/sensors/Points.js was modified to *explicitly* extend THREE.Object3D to support transpiling
  • Loading branch information
keego committed Apr 30, 2018
2 parents c13fffc + b1f8247 commit 05dbe3d
Show file tree
Hide file tree
Showing 18 changed files with 1,197 additions and 859 deletions.
435 changes: 229 additions & 206 deletions build/ros3d.cjs.js

Large diffs are not rendered by default.

435 changes: 229 additions & 206 deletions build/ros3d.esm.js

Large diffs are not rendered by default.

435 changes: 229 additions & 206 deletions build/ros3d.js

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion build/ros3d.min.js

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion es6-support/index.js
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ export * from './navigation/PoseArray'
export * from './navigation/PoseWithCovariance'

export * from './sensors/LaserScan'
export * from './sensors/Particles'
export * from './sensors/Points'
export * from './sensors/PointCloud2'

export * from './urdf/Urdf'
Expand Down
6 changes: 5 additions & 1 deletion es6-transpiler.js
Original file line number Diff line number Diff line change
Expand Up @@ -376,6 +376,10 @@ const transpile = {
.join(',') // put them back into a string
.trim() // trim whitespace

if (!parent) {
logWarning('no parent found for super call disambiguation', { match, child, parent, callee, args })
}

if (callee === parent) {
// we got a super constructor call
if (debugRules.logSuperConstructorCalls) {
Expand All @@ -396,7 +400,7 @@ const transpile = {
}

if (!partsMatch) {
logError('super method call invalid, parts dont match', { match, child, callee, args })
logError('super method call invalid, parts dont match', { match, child, parent, callee, args })
return match
}

Expand Down
67 changes: 67 additions & 0 deletions examples/kitti.html
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />

<script src="https://static.robotwebtools.org/threejs/current/three.js"></script>
<script src="https://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
<script src="https://static.robotwebtools.org/roslibjs/current/roslib.js"></script>
<script src="../build/ros3d.js"></script>

<script>
/**
* Setup all visualization elements when the page is loaded.
*/
function init() {
// Connect to ROS.
var ros = new ROSLIB.Ros({
url : 'ws://localhost:9090'
});

// Create the main viewer.
var viewer = new ROS3D.Viewer({
divID : 'viewer',
width : 800,
height : 600,
antialias : true
});

// Setup a client to listen to TFs.
var tfClient = new ROSLIB.TFClient({
ros : ros,
angularThres : 0.01,
transThres : 0.01,
rate : 10.0,
fixedFrame : 'velo_link'
});

// var texture = new THREE.TextureLoader().load( "https://threejs.org/examples/textures/sprites/ball.png" );

var cloudClient = new ROS3D.PointCloud2({
ros: ros,
tfClient: tfClient,
rootObject: viewer.scene,
topic: '/kitti/velo/pointcloud',
max_pts: 200000,
pointRatio: 3,
messageRatio: 2,
// material: { size: 7, sizeAttenuation: false, alphaTest: 0.5, transparent: true, map: texture },
material: { size: 3, sizeAttenuation: false },
// colorsrc: 'i', colormap: function(i) { return new THREE.Color(3*i,0,1-3*i); }
colorsrc: 'z', colormap: function(z) { z=z+2; return new THREE.Color(z,0,1-z); }
});
}
</script>
</head>

<body onload="init()">
<h1><a href="http://www.cvlibs.net/datasets/kitti">Kitti</a> PointCloud2 Example</h1>
<p>Run the following commands in the terminal then refresh the page.</p>
<ol>
<li><tt>roslaunch ros3djs.launch</tt></li>
<li><tt>rosparam set use_sim_time true</tt></li>
<li><tt>rosbag play -l --clock <a href="https://github.com/tomas789/kitti2bag">kitti_2011_09_26_drive_0002_synced.bag</a></tt></li>
</ol>
<div id="viewer"></div>
</body>
</html>
80 changes: 80 additions & 0 deletions examples/navsatfix.html
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />

<script src="https://static.robotwebtools.org/threejs/current/three.js"></script>
<script src="https://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
<script src="https://static.robotwebtools.org/roslibjs/current/roslib.js"></script>
<script src="../build/ros3d.js"></script>

<script>
/**
* Setup all visualization elements when the page is loaded.
*/
function init() {
// Connect to ROS.
var ros = new ROSLIB.Ros({
url : 'ws://localhost:9090'
});

// Create the main viewer.
var viewer = new ROS3D.Viewer({
divID : 'viewer',
width : 800,
height : 600,
antialias : true
});

// Zoom out the camera to see the trajectory
viewer.cameraControls.zoomOut(20);

// Place the cartesian origin near the gps fixes of the kitti rosbag
var lon0 = 8.4320 * Math.PI/180;
var lat0 = 49.0145 * Math.PI/180;
var alt0 = 116;

// Earth radius for the LLA -> ENU approximate conversion (no earth flattening)
var radius = 6378137;

// This object will be translated to the gps position
var geom = new THREE.SphereGeometry( 0.5, 32, 32 );
var material = new THREE.MeshBasicMaterial( {color: 0xffff00} );
var object3d = new THREE.Mesh(geom, material);

// This function converts the longitude/latitude/altitude of the gps fix
// to the cartesian frame of its rootObject
function convert(lon,lat,alt){
lon = lon * Math.PI/180;
lat = lat * Math.PI/180;
return new THREE.Vector3(
(lon-lon0) * radius * Math.cos(lat),
(lat-lat0) * radius,
(alt-alt0)
);
}

var navsatfix = new ROS3D.NavSatFix({
ros: ros,
topic: '/kitti/oxts/gps/fix',
rootObject: viewer.scene,
object3d: object3d,
convert: convert,
material: { color: 0x00ffff, linewidth: 2 },
keep: 50,
});
}
</script>
</head>

<body onload="init()">
<h1><a href="http://www.cvlibs.net/datasets/kitti">Kitti</a> NavSatFix Example</h1>
<p>Run the following commands in the terminal then refresh the page.</p>
<ol>
<li><tt>roslaunch ros3djs.launch</tt></li>
<li><tt>rosparam set use_sim_time true</tt></li>
<li><tt>rosbag play -l --clock <a href="https://github.com/tomas789/kitti2bag">kitti_2011_09_26_drive_0002_synced.bag</a></tt></li>
</ol>
<div id="viewer"></div>
</body>
</html>
3 changes: 2 additions & 1 deletion examples/pointcloud2.html
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@
ros: ros,
tfClient: tfClient,
rootObject: viewer.scene,
topic: '/camera/depth_registered/points'
topic: '/camera/depth_registered/points',
material: { size: 0.05, color: 0xff00ff }
});
}
</script>
Expand Down
4 changes: 4 additions & 0 deletions examples/ros3djs.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch" />
<node pkg="tf2_web_republisher" type="tf2_web_republisher" name="tf2_web_republisher" />
</launch>
2 changes: 1 addition & 1 deletion package.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
"devDependencies": {
"chai": "^3.5.0",
"debug": "^3.1.0",
"grunt": "^1.0.1",
"grunt": "^1.0.2",
"grunt-contrib-clean": "^1.0.0",
"grunt-contrib-concat": "^1.0.1",
"grunt-contrib-jshint": "^1.1.0",
Expand Down
15 changes: 11 additions & 4 deletions src/depthcloud/DepthCloud.js
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
* * 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)
* * maxDepthPerTile (optional) - the factor with which we control the desired depth range (defaults to 1.0)
* * pointSize (optional) - point size (pixels) for rendered point cloud
* * width (optional) - width of the video stream
* * height (optional) - height of the video stream
Expand All @@ -24,6 +25,7 @@ ROS3D.DepthCloud = function(options) {
this.url = options.url;
this.streamType = options.streamType || 'vp8';
this.f = options.f || 526;
this.maxDepthPerTile = options.maxDepthPerTile || 1.0;
this.pointSize = options.pointSize || 3;
this.width = options.width || 1024;
this.height = options.height || 1024;
Expand Down Expand Up @@ -57,6 +59,7 @@ ROS3D.DepthCloud = function(options) {
'uniform float zOffset;',
'',
'uniform float focallength;',
'uniform float maxDepthPerTile;',
'',
'varying vec2 vUvP;',
'varying vec2 colorP;',
Expand Down Expand Up @@ -160,9 +163,9 @@ ROS3D.DepthCloud = function(options) {
' float z = -depth;',
' ',
' pos = vec4(',
' ( position.x / width - 0.5 ) * z * (1000.0/focallength) * -1.0,',
' ( position.y / height - 0.5 ) * z * (1000.0/focallength),',
' (- z + zOffset / 1000.0) * 2.0,',
' ( 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) );',
Expand Down Expand Up @@ -277,7 +280,11 @@ ROS3D.DepthCloud.prototype.initStreamer = function() {
'varianceThreshold' : {
type : 'f',
value : this.varianceThreshold
}
},
'maxDepthPerTile': {
type : 'f',
value : this.maxDepthPerTile
},
},
vertexShader : this.vertex_shader,
fragmentShader : this.fragment_shader
Expand Down
58 changes: 35 additions & 23 deletions src/models/MeshResource.js
Original file line number Diff line number Diff line change
Expand Up @@ -42,34 +42,46 @@ ROS3D.MeshResource = function(options) {
console.warn(message);
}
};
loader.load(uri, function colladaReady(collada) {
// check for a scale factor in ColladaLoader2
// add a texture to anything that is missing one
if(material !== null) {
collada.scene.traverse(function(child) {
if(child instanceof THREE.Mesh) {
if(child.material === undefined) {
child.material = material;
loader.load(
uri,
function colladaReady(collada) {
// check for a scale factor in ColladaLoader2
// add a texture to anything that is missing one
if(material !== null) {
collada.scene.traverse(function(child) {
if(child instanceof THREE.Mesh) {
if(child.material === undefined) {
child.material = material;
}
}
}
});
}
});
}

that.add(collada.scene);
});
that.add(collada.scene);
},
/*onProgress=*/null,
function onLoadError(error) {
console.error(error);
});
} else if (fileType === '.stl') {
loader = new THREE.STLLoader();
{
loader.load(uri, function ( geometry ) {
geometry.computeFaceNormals();
var mesh;
if(material !== null) {
mesh = new THREE.Mesh( geometry, material );
} else {
mesh = new THREE.Mesh( geometry, new THREE.MeshBasicMaterial( { color: 0x999999 } ) );
}
that.add(mesh);
} );
loader.load(uri,
function ( geometry ) {
geometry.computeFaceNormals();
var mesh;
if(material !== null) {
mesh = new THREE.Mesh( geometry, material );
} else {
mesh = new THREE.Mesh( geometry,
new THREE.MeshBasicMaterial( { color: 0x999999 } ) );
}
that.add(mesh);
},
/*onProgress=*/null,
function onLoadError(error) {
console.error(error);
});
}
}
};
Expand Down
38 changes: 17 additions & 21 deletions src/sensors/LaserScan.js
Original file line number Diff line number Diff line change
Expand Up @@ -9,22 +9,19 @@
* @param options - object with following keys:
*
* * ros - the ROSLIB.Ros connection handle
* * topic - the marker topic to listen to
* * topic - the marker topic to listen to (default '/scan')
* * tfClient - the TF client handle to use
* * color - (optional) color of the points (default 0xFFA500)
* * texture - (optional) Image url for a texture to use for the points. Defaults to a single white pixel.
* * rootObject (optional) - the root object to add this marker to
* * size (optional) - size to draw each point (default 0.05)
* * max_pts (optional) - number of points to draw (default 100)
* * rootObject (optional) - the root object to add this marker to use for the points.
* * max_pts (optional) - number of points to draw (default: 10000)
* * pointRatio (optional) - point subsampling ratio (default: 1, no subsampling)
* * messageRatio (optional) - message subsampling ratio (default: 1, no subsampling)
* * material (optional) - a material object or an option to construct a PointsMaterial.
*/
ROS3D.LaserScan = function(options) {
options = options || {};
this.ros = options.ros;
this.topicName = options.topic || '/scan';
this.color = options.color || 0xFFA500;

this.particles = new ROS3D.Particles(options);

this.points = new ROS3D.Points(options);
this.rosTopic = undefined;
this.subscribe();

Expand All @@ -51,20 +48,19 @@ ROS3D.LaserScan.prototype.subscribe = function(){
};

ROS3D.LaserScan.prototype.processMessage = function(message){
setFrame(this.particles, message.header.frame_id);

if(!this.points.setup(message.header.frame_id)) {
return;
}
var n = message.ranges.length;
for(var i=0;i<n;i++){
var j = 0;
for(var i=0;i<n;i+=this.points.pointRatio){
var range = message.ranges[i];
if(range < message.range_min || range > message.range_max){
this.particles.alpha[i] = 0.0;
}else{
if(range >= message.range_min && range <= message.range_max){
var angle = message.angle_min + i * message.angle_increment;
this.particles.points[i] = new THREE.Vector3( range * Math.cos(angle), range * Math.sin(angle), 0.0 );
this.particles.alpha[i] = 1.0;
this.points.positions.array[j++] = range * Math.cos(angle);
this.points.positions.array[j++] = range * Math.sin(angle);
this.points.positions.array[j++] = 0.0;
}
this.particles.colors[ i ] = new THREE.Color( this.color );
}

finishedUpdate(this.particles, n);
this.points.update(j/3);
};
Loading

0 comments on commit 05dbe3d

Please sign in to comment.