From e3fb0ad8d971d666357c7b49fbeea9e87c06d463 Mon Sep 17 00:00:00 2001 From: Matt Vollrath Date: Tue, 4 Dec 2018 23:36:34 -0500 Subject: [PATCH 1/4] Use CBOR compression for PointCloud2 (#239) * Use CBOR encoding for PointCloud2 * Don't reassign PointCloud2 buffer Reassigning the buffer breaks underlying parts. * Selectable compression in PointCloud2 --- src/sensors/PointCloud2.js | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/sensors/PointCloud2.js b/src/sensors/PointCloud2.js index 2959ed14..511560bf 100644 --- a/src/sensors/PointCloud2.js +++ b/src/sensors/PointCloud2.js @@ -48,6 +48,7 @@ for(var i=0;i<64;i++){decode64.e[decode64.S.charAt(i)]=i;} * * ros - the ROSLIB.Ros connection handle * * topic - the marker topic to listen to (default: '/points') * * tfClient - the TF client handle to use + * * compression (optional) - message compression (default: 'cbor') * * 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) @@ -60,6 +61,7 @@ ROS3D.PointCloud2 = function(options) { options = options || {}; this.ros = options.ros; this.topicName = options.topic || '/points'; + this.compression = options.compression || 'cbor'; this.points = new ROS3D.Points(options); this.rosTopic = undefined; this.subscribe(); @@ -80,7 +82,8 @@ ROS3D.PointCloud2.prototype.subscribe = function(){ this.rosTopic = new ROSLIB.Topic({ ros : this.ros, name : this.topicName, - messageType : 'sensor_msgs/PointCloud2' + messageType : 'sensor_msgs/PointCloud2', + compression: this.compression }); this.rosTopic.subscribe(this.processMessage.bind(this)); }; @@ -93,7 +96,7 @@ ROS3D.PointCloud2.prototype.processMessage = function(msg){ var n, pointRatio = this.points.pointRatio; if (msg.data.buffer) { - this.points.buffer = msg.data.buffer; + this.points.buffer.set(msg.data); n = msg.height*msg.width / pointRatio; } else { n = decode64(msg.data, this.points.buffer, msg.point_step, pointRatio); From 1d2e0411ca5041eaf2adf773104825fb4319f998 Mon Sep 17 00:00:00 2001 From: Matt Vollrath Date: Wed, 16 Jan 2019 07:27:31 -0500 Subject: [PATCH 2/4] Fix PointCloud2 buffers (#244) * Fix PointCloud2 buffers Move the decoding buffer out of Points, since it's only needed during base64 decode. * Clamp n in PointCloud2 binary path Thanks @jubeira for this change. Co-Authored-By: mvollrath --- src/sensors/PointCloud2.js | 14 ++++++++++---- src/sensors/Points.js | 5 ----- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/sensors/PointCloud2.js b/src/sensors/PointCloud2.js index 511560bf..d9fb1413 100644 --- a/src/sensors/PointCloud2.js +++ b/src/sensors/PointCloud2.js @@ -62,8 +62,10 @@ ROS3D.PointCloud2 = function(options) { this.ros = options.ros; this.topicName = options.topic || '/points'; this.compression = options.compression || 'cbor'; + this.max_pts = options.max_pts || 10000; this.points = new ROS3D.Points(options); this.rosTopic = undefined; + this.buffer = null; this.subscribe(); }; ROS3D.PointCloud2.prototype.__proto__ = THREE.Object3D.prototype; @@ -94,16 +96,20 @@ ROS3D.PointCloud2.prototype.processMessage = function(msg){ } var n, pointRatio = this.points.pointRatio; + var bufSz = this.max_pts * msg.point_step; if (msg.data.buffer) { - this.points.buffer.set(msg.data); - n = msg.height*msg.width / pointRatio; + this.buffer = msg.data.slice(0, Math.min(msg.data.byteLength, bufSz)); + n = Math.min(msg.height*msg.width / pointRatio, this.points.positions.array.length / 3); } else { - n = decode64(msg.data, this.points.buffer, msg.point_step, pointRatio); + if (!this.buffer || this.buffer.byteLength < bufSz) { + this.buffer = new Uint8Array(bufSz); + } + n = decode64(msg.data, this.buffer, msg.point_step, pointRatio); pointRatio = 1; } - var dv = new DataView(this.points.buffer.buffer); + var dv = new DataView(this.buffer.buffer); var littleEndian = !msg.is_bigendian; var x = this.points.fields.x.offset; var y = this.points.fields.y.offset; diff --git a/src/sensors/Points.js b/src/sensors/Points.js index ed582628..ab3658cd 100644 --- a/src/sensors/Points.js +++ b/src/sensors/Points.js @@ -40,7 +40,6 @@ ROS3D.Points = function(options) { } this.sn = null; - this.buffer = null; }; ROS3D.Points.prototype.__proto__ = THREE.Object3D.prototype; @@ -48,10 +47,6 @@ ROS3D.Points.prototype.__proto__ = THREE.Object3D.prototype; ROS3D.Points.prototype.setup = function(frame, point_step, fields) { if(this.sn===null){ - // scratch space to decode base64 buffers - if(point_step) { - this.buffer = new Uint8Array( this.max_pts * point_step ); - } // turn fields to a map fields = fields || []; this.fields = {}; From 30630ae44d7be36e1b21e55f25e941f8bb5310c3 Mon Sep 17 00:00:00 2001 From: Matt Vollrath Date: Wed, 16 Jan 2019 07:46:16 -0500 Subject: [PATCH 3/4] Update and normalize EventEmitter2 dependency (#245) --- bower.json | 2 +- package.json | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bower.json b/bower.json index 376b85de..90a90dd3 100644 --- a/bower.json +++ b/bower.json @@ -21,7 +21,7 @@ "Robot Webtools Team (http://robotwebtools.org)" ], "dependencies": { - "eventemitter2": "asyncly/EventEmitter2#^0.4.14", + "eventemitter2": "^4.1.0", "threejs": "mrdoob/three.js#r88", "roslibjs": "RobotWebTools/roslibjs#0.14.0" } diff --git a/package.json b/package.json index b5782ce5..ece58a82 100644 --- a/package.json +++ b/package.json @@ -7,7 +7,7 @@ "main": "./build/ros3d.cjs.js", "module": "./build/ros3d.esm.js", "dependencies": { - "eventemitter2": "~2.2.0", + "eventemitter2": "^4.1.0", "roslib": ">=0.14.0", "three": "^0.88.0" }, From 80f6fde83c23a89b8b560c6345ff25bbb044d288 Mon Sep 17 00:00:00 2001 From: Matt Vollrath Date: Sun, 27 Jan 2019 19:07:34 -0800 Subject: [PATCH 4/4] 1.0.0 (#246) --- CHANGELOG.md | 16 ++++++++++++++++ bower.json | 4 ++-- package.json | 4 ++-- src/Ros3D.js | 2 +- 4 files changed, 21 insertions(+), 5 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0d43068e..0ee6739b 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,21 @@ ## Change Log +### 1.0.0 (2019/01/16 14:48 +00:00) +- [#245](https://github.com/RobotWebTools/ros3djs/pull/245) Update and normalize EventEmitter2 dependency (@mvollrath) +- [#244](https://github.com/RobotWebTools/ros3djs/pull/244) Fix PointCloud2 buffers (@mvollrath) +- [#239](https://github.com/RobotWebTools/ros3djs/pull/239) Use CBOR compression for PointCloud2 (@mvollrath) +- [#238](https://github.com/RobotWebTools/ros3djs/pull/238) Add quaternion copy method call to avoid read-only exception (@epaezrubio) +- [#235](https://github.com/RobotWebTools/ros3djs/pull/235) Use DataTexture for OccupancyGrid (@mvollrath) +- [#232](https://github.com/RobotWebTools/ros3djs/pull/232) add initial support for 3d markers with plane movement (@duwke) +- [#229](https://github.com/RobotWebTools/ros3djs/pull/229) Adding an ES6 only branch (@keego) +- [#223](https://github.com/RobotWebTools/ros3djs/pull/223) fix: pointRatio option in PointCloud2 and LaserScan (@mbredif) +- [#221](https://github.com/RobotWebTools/ros3djs/pull/221) NavSatFix support (@mbredif) +- [#219](https://github.com/RobotWebTools/ros3djs/pull/219) NavSatFix support (@mbredif) +- [#218](https://github.com/RobotWebTools/ros3djs/pull/218) PointCloud2 and LaserScan (@mbredif) +- [#214](https://github.com/RobotWebTools/ros3djs/pull/214) Add ES6 module support (@keego) +- [#210](https://github.com/RobotWebTools/ros3djs/pull/210) add error reporting to MeshResource (@T045T) +- [#206](https://github.com/RobotWebTools/ros3djs/pull/206) Fix links in example and readme (@jihoonl) + ### 0.18.0 (2018/01/04 16:00 +00:00) - [#203](https://github.com/RobotWebTools/ros3djs/pull/203) fix highlighting with Three.js r88 (@T045T) - [#202](https://github.com/RobotWebTools/ros3djs/pull/202) Update coadebase to use Three.js version r88 (@jihoonl) diff --git a/bower.json b/bower.json index 90a90dd3..cce3ee15 100644 --- a/bower.json +++ b/bower.json @@ -2,7 +2,7 @@ "name": "ros3d", "homepage": "https://www.robotwebtools.org", "description": "(BOWER IS DEPRECATING! Please use npm version of ros3d). The standard ROS Javascript Visualization Library", - "version": "0.18.0", + "version": "1.0.0", "license": "BSD-3-Clause", "main": "./src/Ros3D.js", "repository": { @@ -23,6 +23,6 @@ "dependencies": { "eventemitter2": "^4.1.0", "threejs": "mrdoob/three.js#r88", - "roslibjs": "RobotWebTools/roslibjs#0.14.0" + "roslibjs": "RobotWebTools/roslibjs#1.0.0" } } diff --git a/package.json b/package.json index ece58a82..e48c3e67 100644 --- a/package.json +++ b/package.json @@ -2,13 +2,13 @@ "name": "ros3d", "homepage": "https://www.robotwebtools.org", "description": "The standard ROS Javascript Visualization Library", - "version": "0.18.0", + "version": "1.0.0", "license": "BSD-3-Clause", "main": "./build/ros3d.cjs.js", "module": "./build/ros3d.esm.js", "dependencies": { "eventemitter2": "^4.1.0", - "roslib": ">=0.14.0", + "roslib": "^1.0.0", "three": "^0.88.0" }, "devDependencies": { diff --git a/src/Ros3D.js b/src/Ros3D.js index 184b8e8f..b49405d5 100644 --- a/src/Ros3D.js +++ b/src/Ros3D.js @@ -4,7 +4,7 @@ */ var ROS3D = ROS3D || { - REVISION : '0.18.0' + REVISION : '1.0.0' }; // Marker types