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

Use CBOR compression for PointCloud2 #239

Merged
merged 3 commits into from Dec 5, 2018
Merged
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
5 changes: 3 additions & 2 deletions src/sensors/PointCloud2.js
Expand Up @@ -80,7 +80,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: 'cbor'
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we have this configurable as a parameter in options in the constructor? This way it can be set by the user. Might be good to default to no compression to maintain backwards compatibility.

Which makes me wonder why this was not using png compression as default in the first place. In an adapted fork I have good experience with png compression with quite big clouds.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't see any reason to make this configurable. None of the other ROS3D underlying subscriptions have configurable compression.

If "cbor" compression is requested but not available on the server, it will use JSON, so it's already backwards compatible.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When the cbor compression PR lands in rosbridge we will have 3 options: none (JSON), png, and cbor. I have no problem with making the default cbor if omitted (and if it proves robust and bug-free), but I would like the user to have the option for choosing the other 2 types as well.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there a good reason to use another type of compression?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think it would be reasonable for all the visualizer classes to have their topic options exposed. I'd like to be able to override throttle_rate for example. Maybe this should be a separate PR?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So maybe a bytestream of floating point numbers does have enough redundancy for deflate to get value, but not if it is base64 encoded first.

For clients and/or transports that do not support binary messages or per-message deflate, it's possible that we could get good results png encoding a CBOR payload instead of JSON, "cbor_png" compression. This is a good experiment for another day.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's still possible to have a broken combination:

  • ros3djs requesting "cbor" compression
  • old version of roslibjs which can't decode "cbor" will still pass on "cbor" to the server
  • new version of rosbridge which supports "cbor"

So I'll add the optional compression soon and maybe fix roslibjs to not request compression types from the server that it can not decode.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@mvollrath Hi, have you tried visualization_msgs/MarkerArray from octomap_server. It is a bunch of cubes.
My test result with MarkerArray is different from Pointcloud2. The performance for ros3djs when receiving MarkerArray is not acceptable.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

CBOR is bad for MarkerArray iirc, because most of the data is string keys and there's not a lot of content. JSON is generally faster for messages with a lot of different fields, CBOR is generally faster for messages with a few fields and large numeric arrays. Using no roslib compression (plain JSON) is probably best, and I recommend setting up rosbridge to use websocket compression.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the answer. It's very useful to me:D

});
this.rosTopic.subscribe(this.processMessage.bind(this));
};
Expand All @@ -93,7 +94,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);
Expand Down