You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
While using the library to convert PCD data into ROS PointCloud2 messages, I encountered an issue where the offset values for the PointField fields were calculated incorrectly. This resulted in fields like intensity or other attributes being misaligned in the generated PointCloud2 message, causing visualization tools like RViz to display incorrect or missing data.
Expected Behavior
The offset for each PointField should reflect the cumulative byte position of the field within a point, considering the size and count of all preceding fields.
Actual Behavior
The current implementation calculates offset using i * type_.itemsize, which assumes a fixed-size field alignment without considering the actual data layout or field sizes. This leads to incorrect offset values for fields that do not align sequentially (e.g., fields with different sizes or counts).
Steps to Reproduce
Use the library to generate a PointCloud2 message from a PCD file with fields of varying sizes and counts, such as:
x, y, z (float32)
intensity (uint8)
return_type (uint8)
channel (uint16)
Publish the PointCloud2 message in ROS.
Attempt to visualize the data in RViz or CloudCompare.
Example Code
Here is the problematic snippet:
for i, (field, type_, count) in enumerate(zip(self.fields, self.types, self.counts)):
type_ = np.dtype(type_)
fields.append(
PointField(
name=field,
offset=i * type_.itemsize, # Incorrect offset calculation
datatype=NPTYPE_TO_PFTYPE[type_],
count=count,
)
)
Suggested Fix
The offset should be calculated as the cumulative sum of the sizes of all preceding fields, adjusted for the field's count. For example:
@tokuda99
Thank you for sharing your findings. It looks like a solid solution.
Could you please open a pull request with your changes so we can review them together?
Description
While using the library to convert PCD data into ROS
PointCloud2
messages, I encountered an issue where theoffset
values for thePointField
fields were calculated incorrectly. This resulted in fields likeintensity
or other attributes being misaligned in the generatedPointCloud2
message, causing visualization tools like RViz to display incorrect or missing data.Expected Behavior
The
offset
for eachPointField
should reflect the cumulative byte position of the field within a point, considering the size and count of all preceding fields.Actual Behavior
The current implementation calculates
offset
usingi * type_.itemsize
, which assumes a fixed-size field alignment without considering the actual data layout or field sizes. This leads to incorrectoffset
values for fields that do not align sequentially (e.g., fields with different sizes or counts).Steps to Reproduce
x, y, z
(float32)intensity
(uint8)return_type
(uint8)channel
(uint16)PointCloud2
message in ROS.Example Code
Here is the problematic snippet:
Suggested Fix
The
offset
should be calculated as the cumulative sum of the sizes of all preceding fields, adjusted for the field'scount
. For example:Impact
This issue causes data misalignment in the
PointCloud2
message, leading to:Please let me know if you need further details or examples to reproduce the issue. Thank you for addressing this!
The text was updated successfully, but these errors were encountered: