[Documentation] [TitleIndex] [WordIndex

Overview

This package is a temporary home for the proposed new point cloud messages and related infrastructure. The goal is to give users maximal flexibility and ease in working with point clouds and channel data, without sacrificing efficiency.

Messages

The new PointCloud message interleaves all channels into a binary blob, with info about structure in fields.

PointCloud.msg:

Header header

# Point data is stored as a binary blob.
PointField[] fields
uint8[]      data

# 2D structure of the point cloud. If the cloud is unordered,
# height is 1 and width is the length of the point cloud.
uint32 width
uint32 height

bool is_dense     # True if there are no invalid points
bool is_bigendian

PointField.msg:

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
uint32 offset
uint8  datatype

Discussion:

Registering a user-defined point type

We provide macros for registering a user-defined point struct with the publish/subscribe infrastructure. There are two versions. If your struct is flat (only scalar data members) and all field names are standard, you can use the concise form POINT_CLOUD_REGISTER_FLAT_POINT_STRUCT. If your struct contains struct members, array members, or has any non-standard named fields, you should use the more general POINT_CLOUD_REGISTER_POINT_STRUCT. For example:

#include <stdint.h>
#include "point_cloud_redesign/register_point_struct.h"

namespace my_ns {

struct MyPoint
{
  float x;
  float y;
  float z;

  uint32_t w;
};

} // namespace my_ns

// Must be used in the global namespace with the fully-qualified name
// of the point type.
POINT_CLOUD_REGISTER_FLAT_POINT_STRUCT(
  my_ns::MyPoint,
  (float, x)
  (float, y)
  (float, z)
  (uint32_t, w));


namespace my_ns2 {

struct Position
{
  float x;
  float y;
  float z;
}

struct MyComplexPoint
{
  Position pos;
  uint32_t w;
  float normal[3];
};

} // namespace my_ns2

POINT_CLOUD_REGISTER_POINT_STRUCT(
  my_ns2::MyComplexPoint,
  (float,    pos.x,     x)
  (float,    pos.y,     y)
  (float,    pos.z,     z)
  (uint32_t, w,         w)
  (float,    normal[0], normal_x)
  (float,    normal[1], normal_y)
  (float,    normal[2], normal_z));

The registration list contains (datatype, accessor, tag) 3-tuples. In the flat case, the accessor and tag are the same.

The registration macro, incidentally, also registers the point struct with Boost.Fusion as an associative type, meaning you can access fields by tag:

#include <boost/fusion/sequence/intrinsic/at_key.hpp>

my_ns::MyPoint pt1 = {1.0, 2.5, 6.1, 42};
MyComplexPoint pt2 = {{1.0, 2.5, 6.1}, 42, {0.0, 1.0, 0.0}};

printf("pt1 has x = %f\n", pt1.x);
printf("pt2 has x = %f\n", pt2.pos.x);
// is identical to...
printf("pt1 has x = %f\n", boost::fusion::at_key<point_cloud::fields::x>(pt1));
printf("pt2 has x = %f\n", boost::fusion::at_key<point_cloud::fields::x>(pt2));

The syntax could be made less horrible; the point is that this at least opens the possibility of writing generic point cloud algorithms that operate efficiently on arbitrary user-defined point types.

Limitations:

Discussion:

Publishing point clouds

There is a specialized point_cloud::Publisher for point clouds (doc). It's templated on a registered point type. The publish() methods take point clouds as a container of points (plus dimensions for structured clouds), where the container is anything recognized by Boost.Range. That includes STL containers, fixed-size arrays, pairs of pointers or iterators, etc.

Usage example:

#include "my_point.h"
#include <point_cloud_redesign/publisher.h>
#include <ros/ros.h>

int main(int argc, char** argv)
{
  std::vector<my_ns::MyPoint> pt_cloud;
  my_ns::MyPoint pt = {1.0, 2.5, 6.1, 42};
  pt_cloud.push_back(pt);

  ros::init(argc, argv, "point_cloud_publisher");
  ros::NodeHandle nh;
  point_cloud::Publisher<my_ns::MyPoint> pub;
  pub.advertise(nh, "cloud", 1);

  ros::Rate loop_rate(4);
  while (nh.ok()) {
    pub.publish(pt_cloud); // unordered, may be invalid points
    ros::spinOnce();
    loop_rate.sleep();
  }
}

Discussion:

Subscribing to point clouds

There is a specialized point_cloud::Subscriber for point clouds (doc). It's templated on a registered point type. The subscriber callback takes a const-ptr to point_cloud::PointCloud (doc) which is also templated on the point type.

Usage example:

#include "my_point.h"
#include <point_cloud_redesign/subscriber.h>

void callback(const point_cloud::PointCloud<my_ns::MyPoint>::ConstPtr& msg)
{
  printf("Cloud: width = %u, height = %u\n", msg->width, msg->height);
  BOOST_FOREACH(const my_ns::MyPoint& pt, msg->points)
    printf("\t(%f, %f, %f, %u)\n", pt.x, pt.y, pt.z, pt.w);
}

int main(int argc, char** argv)
{
  ros::init(argc, argv, "point_cloud_listener");
  ros::NodeHandle nh;
  point_cloud::Subscriber<my_ns::MyPoint> sub;
  sub.subscribe(nh, "cloud", 1, callback);
  ros::spin();
}

Limitations:

Ethan's Initial Reactions / Questions

Stride -> my understanding was that there was not only a stride, but there was a stride per PointField. This allows for either interleaved or separate planes. I'm not convinced that always interleaving is what we want (I like 128 bit alignment for instance, and I don't like padding). Is this infeasible for some reason? Perhaps as an alternative some sort of point class that is a collection of the new new point clouds, but does not have disgusting syntax. Then one could have a piece that is 128 bit aligned, and a piece that is unaligned and some weird size, and not waste space on padding.

With all of the possible point structs how does one tell if a given point is invalid or valid if the cloud is not dense?

Having loads of custom publishers / subscribers feels wrong (it's one thing if it's just image_transport, it's another if you have to look up the appropriate publisher type every time you want to publish something). Can we get around this somehow? Would it require a ROS API change? It seems like the hooks should be available to do whatever needs to be done within a ROS publisher / subscriber. Template specialization feels like the right solution here for C++. Of course this brings up:

How does other language support work?

For now I think 128-bit alignment is the most important, but I could imagine scenarios where other alignments might be important. For example 256-bit is already potentially important for some graphics card applications, and will be important in future versions of SSE (SSE5).

It seems like we need some enums to standardize names for fields. I don't want one person using "x" and another using "X" for instance. I'd like all the normals called the same things, etc.

Notes 11/16/09


2024-11-09 14:28