From 0cd38040b619ba16f3d7ded61ef824bb5af77c91 Mon Sep 17 00:00:00 2001 From: Matt Vollrath Date: Thu, 17 Jan 2019 12:42:02 -0500 Subject: [PATCH] Use CBOR by default for OccupancyGrid Proven faster for non-homogeneous data. --- src/navigation/OccupancyGridClient.js | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/navigation/OccupancyGridClient.js b/src/navigation/OccupancyGridClient.js index 44620d4c..a215e76a 100644 --- a/src/navigation/OccupancyGridClient.js +++ b/src/navigation/OccupancyGridClient.js @@ -16,6 +16,7 @@ * * topic (optional) - the map topic to listen to * * continuous (optional) - if the map should be continuously loaded (e.g., for SLAM) * * tfClient (optional) - the TF client handle to use for a scene node + * * compression (optional) - message compression (default: 'cbor') * * rootObject (optional) - the root object to add this marker to * * offsetPose (optional) - offset pose of the grid visualization, e.g. for z-offset (ROSLIB.Pose type) * * color (optional) - color of the visualized grid @@ -26,6 +27,7 @@ ROS3D.OccupancyGridClient = function(options) { options = options || {}; this.ros = options.ros; this.topicName = options.topic || '/map'; + this.compression = options.compression || 'cbor'; this.continuous = options.continuous; this.tfClient = options.tfClient; this.rootObject = options.rootObject || new THREE.Object3D(); @@ -56,7 +58,7 @@ ROS3D.OccupancyGridClient.prototype.subscribe = function(){ ros : this.ros, name : this.topicName, messageType : 'nav_msgs/OccupancyGrid', - compression : 'png' + compression : this.compression }); this.rosTopic.subscribe(this.processMessage.bind(this)); };