API review
Proposer: Patrick
Present at review:
- Tully
- Radu
- Josh
- Kurt
Overview
The old channel-based sensor_msgs/PointCloud was found to be very awkward to use. It only supports float32 channels, forcing dangerous casting for other kinds of data. It also does not map well to how developers represent point cloud data structures, requiring a lot of data shuffling to put them in message format.
The new point cloud message represents point data as a binary blob of point structures. Metadata describes the names and types of the point fields, as well as their binary layout.
#This message holds a collection of nD points, as a binary blob. Header header # 2D structure of the point cloud. If the cloud is unordered, # height is 1 and width is the length of the point cloud. uint32 height uint32 width # Describes the channels and their layout in the binary data blob. PointField[] fields bool is_bigendian # Is this data bigendian? uint32 point_step # Length of a point in bytes uint32 row_step # Length of a row in bytes uint8[] data # Actual point data, size is (row_step*height) bool is_dense # True if there are no invalid points
#This message holds the description of one point entry in the PointCloud2 message format. uint8 INT8 = 1 uint8 UINT8 = 2 uint8 INT16 = 3 uint8 UINT16 = 4 uint8 INT32 = 5 uint8 UINT32 = 6 uint8 FLOAT32 = 7 uint8 FLOAT64 = 8 string name # Name of the field. Should follow standard conventions. uint32 offset # Byte offset from the start of the point uint8 datatype # Enum for the scalar data type uint32 size # Number of elements
NOTE: The size field is a new addition in trunk. Previously it was very awkward to encode large array fields like float pfhDescriptor[81].
Wrapping user point types in C++
One of the motivating desires behind PointCloud2 is to allow the serialized data format to be the same as the in-memory format used by developers for collections of points. This makes the message more intuitive (despite being a binary blob) and allows (de)serialization of the point data to be a simple memcpy.
point_cloud_redesign contains proof-of-concept Publisher and Subscriber classes that translate between user-declared point structs and the PointCloud2 message. Somewhat like image_transport, they allow the user to send/receive their data in the most convenient format without worrying how it is actually represented over the wire. We don't need to debate the C++ API in this meeting, but I think it helps demonstrate the ease-of-use and efficiency arguments for the new message.
Registering a point struct with the system. This demonstrates using sub-structs and arrays:
   1 struct Position
   2 {
   3   float x;
   4   float y;
   5   float z;
   6 };
   7 
   8 struct MyPoint
   9 {
  10   Position pos;
  11   uint32_t w;
  12   float normal[3];
  13 };
  14 
  15 // Registration macro
  16 // The format is (type, field accessor, name)
  17 POINT_CLOUD_REGISTER_POINT_STRUCT(
  18   MyPoint,
  19   (float,    pos.x,   x)
  20   (float,    pos.y,   y)
  21   (float,    pos.z,   z)
  22   (uint32_t, w,       w)
  23   (float[3], normal, normal));
Publishing a point cloud:
   1 // Point cloud class templated on user point type,
   2 // intended for easy use in code.
   3 MyPoint pt;
   4 point_cloud::PointCloud<MyPoint> pt_cloud;
   5 pt_cloud.points.push_back(pt);
   6 pt_cloud.width = pt_cloud.height = 1;
   7 
   8 // Point cloud publisher understands how to translate the
   9 // user point type into a PointCloud2 message.
  10 point_cloud::Publisher<MyPoint> pub;
  11 pub.advertise(node_handle, "cloud_topic", 1);
  12 pub.publish(pt_cloud);
Subscribing to a point cloud:
   1 void cloudCallback(const point_cloud::PointCloud<MyPoint>::ConstPtr& msg)
   2 {
   3   printf("Cloud: width = %u, height = %u\n", msg->width, msg->height);
   4   BOOST_FOREACH(const Point& pt, msg->points) {
   5     printf("\tpos = (%f, %f, %f), w = %u, normal = (%f, %f, %f)\n",
   6            pt.pos.x, pt.pos.y, pt.pos.z, pt.w,
   7            pt.normal[0], pt.normal[1], pt.normal[2]);
   8   }
   9 }
  10 
  11 point_cloud::Subscriber<MyPoint> sub;
  12 sub.subscribe(node_handle, "cloud_topic", 1, cloudCallback);
Question / concerns / comments
Josh
- size in PointField also lets you encode "xyz" as a single element... I assume we want to discourage that? 
- Is size in bytes? The comment seems to imply it's actually a count... if so I think count is a better name. 
- The comment for name says "should follow standard conventions". Can we put those conventions in the comments? 
Meeting agenda
- Optimizations - Publisher is already one memcpy
- Nodelets?
- Intra-process passing through shared_ptr to user data without PointCloud2 transformations (not done) - High priority for efficient nodelets
- Under the hood, publish/subscribe the templated point cloud type. roscpp detects if the types are the same, will pass through the shared_ptr if they are.
- Need to specialize Serializer on templated PointCloud. 
 
- Subscriber-side memcpy optimizations (not done) - Coalesce memcpy's for fields within the point struct
- If Publisher/Subscriber agree exactly on format, do one memcpy
 
 
- point_cloud_transport - Do we even need it? Just specialize ROS Publisher/Subscriber to do the right thing?
- Holding up release of PCL. Need at least the PointCloud message filter. 
 
Conclusion
Messages (Tully):
- size -> count 
PCL (Radu):
- Move point_cloud_redesign magic into PCL as internal implementation details.
Point cloud transport (Patrick):
- Evaluate whether can implement by customizing roscpp classes.
- (Josh) Send me some sample code customizing Serializer with stateful create() function.
- Plan to release immediately after ROS 1.1.
Package status change mark change manifest)
 Action items that need to be taken. Action items that need to be taken.
 Major issues that need to be resolved Major issues that need to be resolved
