ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
First off, you probably don't want to send a PointCloud2, buth rather a Depth Image. The difference is:
A Depth Image can later be converted into a PointCloud2, given the camera parameters. Some more tips:
To answer the second of your questions:
What is the purpose of the is_dense field? Does it change how the bytes should be formatted in the msg.data property?
That's answered very shortly in the PointCloud2 comments. Basically it's like this:
height
== 1 (and therefore width
== number of points, since height * width must equal number of points). Organized means something like height == 240
, width == 320
, and that's usual for point clouds that come from a 3D camera. The useful thing about this is that there is a one-to-one mapping between a pixel and a point, which allows more efficient algorithms.std::numeric_limits<float>::quiet_NaN()
.Strictly speaking, these two things are orthogonal (that's why it makes sense to keep the concepts separate), but in 99.9% of cases it's coupled:
The is_dense
flag is used a lot inside the PCL; mostly, there is logic like "if the cloud is not dense, iterate over all points and remove the invalid points; otherwise, proceed".
2 | No.2 Revision |
First off, you probably don't want to send a PointCloud2, buth rather a Depth Image. The difference is:
A Depth Image can later be converted into a PointCloud2, given the camera parameters. Some more tips:
To answer the second of your questions:
What is the purpose of the is_dense field? Does it change how the bytes should be formatted in the msg.data property?
That's answered very shortly in the PointCloud2 comments. Basically it's like this:
height
== 1 (and therefore width
== number of points, since height * width must equal number of points). Organized means something like height == 240
, width == 320
, and that's usual for point clouds that come from a 3D camera. The useful thing about this is that there is a one-to-one mapping between a pixel and a point, which allows more efficient algorithms.std::numeric_limits<float>::quiet_NaN()
.Strictly speaking, these two things are orthogonal (that's why it makes sense to keep the concepts separate), but in 99.9% of cases it's coupled:
The is_dense
flag is used a lot inside the PCL; mostly, there is logic like "if the cloud is not dense, iterate over all points and remove the invalid points; otherwise, proceed".
One final tip: Instead of filling out the PointCloud2 message fields directly, it's much more comfortable to fill out a pcl::PointCloud<T>
message instead and publish it via pcl_ros, which will do the conversion to a PointCloud2 automatically.
3 | No.3 Revision |
First off, you probably don't want to send a PointCloud2, buth rather a Depth Image. The difference is:
A Depth Image can later be converted into a PointCloud2, given the camera parameters. Some more tips:
To answer the second of your questions:
What is the purpose of the is_dense field? Does it change how the bytes should be formatted in the msg.data property?
That's answered very shortly in the PointCloud2 comments. Basically it's like this:
height
== 1 (and therefore width
== number of points, since height * width must equal number of points). Organized means something like height == 240
, width == 320
, and that's usual for point clouds that come from a 3D camera. The useful thing about this is that there is a one-to-one mapping between a pixel and a point, which allows more efficient algorithms.std::numeric_limits<float>::quiet_NaN()
.Strictly speaking, these two things are orthogonal (that's why it makes sense to keep the concepts separate), but in 99.9% of cases it's coupled:
The is_dense
flag is used a lot inside the PCL; mostly, there is logic like "if the cloud is not dense, iterate over all points and remove the invalid points; otherwise, proceed".
One final tip: Instead of filling out the PointCloud2 message fields directly, it's much more comfortable to fill out a pcl::PointCloud<T>
message instead and publish it via pcl_ros, which will do the conversion to a PointCloud2 automatically.
The count property of the fields is still a bit confusing
From the PCL docs:
COUNT - specifies how many elements does each dimension have. For example, x data usually has 1 element, but a feature descriptor like the VFH has 308. Basically this is a way to introduce n-D histogram descriptors at each point, and treating them as a single contiguous block of memory.
(This documentation is about the PCD file format, but this part is true for PointCloud2 as well).
Most "common" fields like x, y, z all have count == 1 each. Both rbg
and rgba
have count == 1 for the whole color tuple (because they are represented as 3 or 4 chars concatenated into a float -- you can see why I recommend not filling the PointCloud2 message directly).
If you want a list of all PCL point types that have count > 1, look at common/include/pcl/impl/point_types.hpp. All point types that end in a number have the respective count (e.g., pcl::FPFHSignature33
has count == 33).
I've uploaded a small test program to this gist that publishes a PointCloud<pcl::FPFHSignature33>
. If you do a rostopic echo /cloud
, you'll see this:
header:
seq: 37
stamp:
secs: 1463732445
nsecs: 246704000
frame_id: some_frame
height: 1
width: 1
fields:
-
name: fpfh
offset: 0
datatype: 7
count: 33
is_bigendian: False
point_step: 132
row_step: 132
data: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 41, 92, 187, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
is_dense: True
Each point has a single field with a count of 33 and datatype 7, meaning float[33]
. Since a float takes 4 bytes, point_step == 4 * 33 = 132
, and row_step == width * point_step = 132
. The line p.histogram[15] = 23.42f;
from my gist translates to the four bytes 41, 92, 187, 65
in the middle.
4 | No.4 Revision |
First off, you probably don't want to send a PointCloud2, buth rather a Depth Image. The difference is:
A Depth Image can later be converted into a PointCloud2, given the camera parameters. Some more tips:
To answer the second of your questions:
What is the purpose of the is_dense field? Does it change how the bytes should be formatted in the msg.data property?
That's answered very shortly in the PointCloud2 comments. Basically it's like this:
height
== 1 (and therefore width
== number of points, since height * width must equal number of points). Organized means something like height == 240
, width == 320
, and that's usual for point clouds that come from a 3D camera. The useful thing about this is that there is a one-to-one mapping between a pixel and a point, which allows more efficient algorithms.std::numeric_limits<float>::quiet_NaN()
.Strictly speaking, these two things are orthogonal (that's why it makes sense to keep the concepts separate), but in 99.9% of cases it's coupled:
The is_dense
flag is used a lot inside the PCL; mostly, there is logic like "if the cloud is not dense, iterate over all points and remove the invalid points; otherwise, proceed".
One final tip: Instead of filling out the PointCloud2 message fields directly, it's much more comfortable to fill out a pcl::PointCloud<T>
message instead and publish it via pcl_ros, which will do the conversion to a PointCloud2 automatically.
The count property of the fields is still a bit confusing
From the PCL docs:
COUNT - specifies how many elements does each dimension have. For example, x data usually has 1 element, but a feature descriptor like the VFH has 308. Basically this is a way to introduce n-D histogram descriptors at each point, and treating them as a single contiguous block of memory.
(This documentation is about the PCD file format, but this part is true for PointCloud2 as well).
Most "common" fields like x, y, z all have count == 1 each. Both rbg
and rgba
have count == 1 for the whole color tuple (because they are represented as 3 or 4 chars concatenated into a float -- you can see why I recommend not filling the PointCloud2 message directly).
If you want a list of all PCL point types that have count > 1, look at common/include/pcl/impl/point_types.hpp. All point types that end in a number have the respective count (e.g., pcl::FPFHSignature33
has count == 33).
I've uploaded a small test program to this gist that publishes a PointCloud<pcl::FPFHSignature33>
. If you do a rostopic echo /cloud
, you'll see this:
header:
seq: 37
stamp:
secs: 1463732445
nsecs: 246704000
frame_id: some_frame
height: 1
width: 1
fields:
-
name: fpfh
offset: 0
datatype: 7
count: 33
is_bigendian: False
point_step: 132
row_step: 132
data: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 41, 92, 187, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
is_dense: True
Each point has a single field with a count of 33 and datatype 7, meaning float[33]
. Since a float takes 4 bytes, point_step == 4 * 33 = 132
, and row_step == width * point_step = 132
. The line p.histogram[15] = 23.42f;
from my gist translates to the four bytes 41, 92, 187, 65
in the middle.
data
.