Now it seems you can do very well without the PCL library in both Python and C++.
For Python, there is the sensor_msgs.point_cloud2 package with the read_points method.
For C++, you can use sensor_msgs::PointCloud2Iterator to iterate the fields (like "x" for the x-coordinate, or "r" for the red color). And for creating/basic manipulation with PointCloud2 clouds, there is the sensor_msgs::PointCloud2Modifier class, which allows you to conveniently set the fields structure, resize or clear a point cloud.
Example usage of the C++ interface (taken and simplified from ros-perception/image_pipeline):
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud2_iterator.h>
using namespace sensor_msgs;
PointCloud2Ptr points_msg = boost::make_shared<PointCloud2>();
points_msg->header = ...; // TODO fill in header
points_msg->height = mat.rows; // if this is a "full 3D" pointcloud, height is 1; if this is Kinect-like pointcloud, height is the vertical resolution
points_msg->width = mat.cols;
points_msg->is_bigendian = false;
points_msg->is_dense = false; // there may be invalid points
sensor_msgs::PointCloud2Modifier pcd_modifier(*points_msg);
// this call also resizes the data structure according to the given width, height and fields
pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
sensor_msgs::PointCloud2Iterator<float> iter_x(*points_msg, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(*points_msg, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(*points_msg, "z");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(*points_msg, "r");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(*points_msg, "g");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(*points_msg, "b");
for (...) // TODO get/generate point coordinates and colors
{
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b)
{
// TODO fill in x, y, z, r, g, b local variables
*iter_x = x;
*iter_y = y;
*iter_z = z;
*iter_r = r;
*iter_g = g;
*iter_b = b;
}
}
You can also apply a transform directly to PointCloud2 type using the tf2_sensor_msgs (both C++ and Python interface, since at least Indigo):
#include <tf2_sensor_msgs/tf2_sensor_msgs.h>
#include <sensor_msgs/PointCloud2.h>
#include <geometry_msgs/TransformStamped.h>
const sensor_msgs::PointCloud2 cloud_in, cloud_out;
const geometry_msgs::TransformStamped transform;
// TODO load everything
tf2::doTransform (cloud_in, cloud_out, transform);
Or in Python:
from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
cloud_out = do_transform_cloud(cloud_in, transform)
None of the codes was really tested, though I intend to use them tomorrow. If you test them and find a bug, please edit my answer. I really wonder why there aren't more tutorials for this kind of essential conversions.