Skip to content

Commit 9a53823

Browse files
committed
Use structured NumPy points.dtype.itemsize as default point_step in create_cloud
Signed-off-by: xndcn <[email protected]>
1 parent e8256c0 commit 9a53823

File tree

2 files changed

+13
-3
lines changed

2 files changed

+13
-3
lines changed

sensor_msgs_py/sensor_msgs_py/point_cloud2.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -250,8 +250,10 @@ def create_cloud(
250250
for each point, with the elements of each iterable being the
251251
values of the fields for that point (in the same order as
252252
the fields parameter)
253-
:param point_step: Point step size in bytes. Calculated from the given fields by default.
254-
(Type: optional of integer)
253+
:param point_step: Point step size in bytes. If not provided, it is calculated
254+
from the given fields, except when 'points' is a structured
255+
NumPy array, in which case points.dtype.itemsize is used.
256+
(Type: optional integer)
255257
:return: The point cloud as sensor_msgs.msg.PointCloud2
256258
"""
257259
# Check if input is numpy array
@@ -266,7 +268,7 @@ def create_cloud(
266268
points,
267269
dtype=dtype_from_fields(fields, point_step))
268270
else:
269-
assert points.dtype == dtype_from_fields(fields, point_step), \
271+
assert points.dtype == dtype_from_fields(fields, point_step or points.dtype.itemsize), \
270272
'PointFields and structured NumPy array dtype do not match for all fields! \
271273
Check their field order, names and types.'
272274
else:

sensor_msgs_py/test/test_point_cloud2.py

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -296,10 +296,18 @@ def test_create_cloud(self):
296296
def test_create_cloud_itemsize(self):
297297

298298
with self.assertRaises(AssertionError):
299+
dtype_from_fields = point_cloud2.dtype_from_fields(fields)
299300
point_cloud2.create_cloud(
301+
Header(frame_id='frame'),
302+
fields,
303+
points_end_padding,
304+
dtype_from_fields.itemsize)
305+
306+
thispcd = point_cloud2.create_cloud(
300307
Header(frame_id='frame'),
301308
fields,
302309
points_end_padding)
310+
self.assertEqual(thispcd.point_step, itemsize_end_padding)
303311

304312
thispcd = point_cloud2.create_cloud(
305313
Header(frame_id='frame'),

0 commit comments

Comments
 (0)