37
37
sensor_msgs/src/sensor_msgs/point_cloud2.py
38
38
"""
39
39
40
+ import array
40
41
from collections import namedtuple
41
- import ctypes
42
- import math
43
- import struct
44
42
import sys
43
+ from typing import Iterable , List , NamedTuple , Optional
45
44
45
+ import numpy as np
46
+ from numpy .lib .recfunctions import (structured_to_unstructured ,
47
+ unstructured_to_structured )
46
48
from sensor_msgs .msg import PointCloud2 , PointField
49
+ from std_msgs .msg import Header
47
50
48
51
49
52
_DATATYPES = {}
50
- _DATATYPES [PointField .INT8 ] = ('b' , 1 )
51
- _DATATYPES [PointField .UINT8 ] = ('B' , 1 )
52
- _DATATYPES [PointField .INT16 ] = ('h' , 2 )
53
- _DATATYPES [PointField .UINT16 ] = ('H' , 2 )
54
- _DATATYPES [PointField .INT32 ] = ('i' , 4 )
55
- _DATATYPES [PointField .UINT32 ] = ('I' , 4 )
56
- _DATATYPES [PointField .FLOAT32 ] = ('f' , 4 )
57
- _DATATYPES [PointField .FLOAT64 ] = ('d' , 8 )
58
-
59
-
60
- def read_points (cloud , field_names = None , skip_nans = False , uvs = []):
53
+ _DATATYPES [PointField .INT8 ] = np .dtype (np .int8 )
54
+ _DATATYPES [PointField .UINT8 ] = np .dtype (np .uint8 )
55
+ _DATATYPES [PointField .INT16 ] = np .dtype (np .int16 )
56
+ _DATATYPES [PointField .UINT16 ] = np .dtype (np .uint16 )
57
+ _DATATYPES [PointField .INT32 ] = np .dtype (np .int32 )
58
+ _DATATYPES [PointField .UINT32 ] = np .dtype (np .uint32 )
59
+ _DATATYPES [PointField .FLOAT32 ] = np .dtype (np .float32 )
60
+ _DATATYPES [PointField .FLOAT64 ] = np .dtype (np .float64 )
61
+
62
+ DUMMY_FIELD_PREFIX = 'unnamed_field'
63
+
64
+
65
+ def read_points (
66
+ cloud : PointCloud2 ,
67
+ field_names : Optional [List [str ]] = None ,
68
+ skip_nans : bool = False ,
69
+ uvs : Optional [Iterable ] = None ,
70
+ reshape_organized_cloud : bool = False ) -> np .ndarray :
61
71
"""
62
72
Read points from a sensor_msgs.PointCloud2 message.
63
73
@@ -67,56 +77,92 @@ def read_points(cloud, field_names=None, skip_nans=False, uvs=[]):
67
77
:param skip_nans: If True, then don't return any point with a NaN value.
68
78
(Type: Bool, Default: False)
69
79
:param uvs: If specified, then only return the points at the given
70
- coordinates. (Type: Iterable, Default: empty list)
71
- :return: Generator which yields a list of values for each point.
80
+ coordinates. (Type: Iterable, Default: None)
81
+ :param reshape_organized_cloud: Returns the array as an 2D organized point cloud if set.
82
+ :return: Structured NumPy array containing all points.
72
83
"""
73
84
assert isinstance (cloud , PointCloud2 ), \
74
- 'cloud is not a sensor_msgs.msg.PointCloud2'
75
- fmt = _get_struct_fmt (cloud .is_bigendian , cloud .fields , field_names )
76
- width , height , point_step , row_step , data , isnan = \
77
- cloud .width , cloud .height , \
78
- cloud .point_step , cloud .row_step , \
79
- cloud .data , math .isnan
80
-
81
- unpack_from = struct .Struct (fmt ).unpack_from
82
-
83
- if skip_nans :
84
- if uvs :
85
- for u , v in uvs :
86
- p = unpack_from (data , (row_step * v ) + (point_step * u ))
87
- has_nan = False
88
- for pv in p :
89
- if isnan (pv ):
90
- has_nan = True
91
- break
92
- if not has_nan :
93
- yield p
94
- else :
95
- for v in range (height ):
96
- offset = row_step * v
97
- for u in range (width ):
98
- p = unpack_from (data , offset )
99
- has_nan = False
100
- for pv in p :
101
- if isnan (pv ):
102
- has_nan = True
103
- break
104
- if not has_nan :
105
- yield p
106
- offset += point_step
107
- else :
108
- if uvs :
109
- for u , v in uvs :
110
- yield unpack_from (data , (row_step * v ) + (point_step * u ))
111
- else :
112
- for v in range (height ):
113
- offset = row_step * v
114
- for u in range (width ):
115
- yield unpack_from (data , offset )
116
- offset += point_step
85
+ 'Cloud is not a sensor_msgs.msg.PointCloud2'
86
+
87
+ # Cast bytes to numpy array
88
+ points = np .ndarray (
89
+ shape = (cloud .width * cloud .height , ),
90
+ dtype = dtype_from_fields (cloud .fields ),
91
+ buffer = cloud .data )
92
+
93
+ # Keep only the requested fields
94
+ if field_names is not None :
95
+ assert all (field_name in points .dtype .names for field_name in field_names ), \
96
+ 'Requests field is not in the fields of the PointCloud!'
97
+ # Mask fields
98
+ points = points [list (field_names )]
99
+
100
+ # Swap array if byte order does not match
101
+ if bool (sys .byteorder != 'little' ) != bool (cloud .is_bigendian ):
102
+ points = points .byteswap (inplace = True )
103
+
104
+ # Check if we want to drop points with nan values
105
+ if skip_nans and not cloud .is_dense :
106
+ # Init mask which selects all points
107
+ not_nan_mask = np .ones (len (points ), dtype = bool )
108
+ for field_name in points .dtype .names :
109
+ # Only keep points without any non values in the mask
110
+ not_nan_mask = np .logical_and (
111
+ not_nan_mask , ~ np .isnan (points [field_name ]))
112
+ # Select these points
113
+ points = points [not_nan_mask ]
114
+
115
+ # Select points indexed by the uvs field
116
+ if uvs is not None :
117
+ # Don't convert to numpy array if it is already one
118
+ if not isinstance (uvs , np .ndarray ):
119
+ uvs = np .fromiter (uvs , int )
120
+ # Index requested points
121
+ points = points [uvs ]
122
+
123
+ # Cast into 2d array if cloud is 'organized'
124
+ if reshape_organized_cloud and cloud .height > 1 :
125
+ points = points .reshape (cloud .width , cloud .height )
126
+
127
+ return points
128
+
129
+
130
+ def read_points_numpy (
131
+ cloud : PointCloud2 ,
132
+ field_names : Optional [List [str ]] = None ,
133
+ skip_nans : bool = False ,
134
+ uvs : Optional [Iterable ] = None ,
135
+ reshape_organized_cloud : bool = False ) -> np .ndarray :
136
+ """
137
+ Read equally typed fields from sensor_msgs.PointCloud2 message as a unstructured numpy array.
117
138
139
+ This method is better suited if one wants to perform math operations
140
+ on e.g. all x,y,z fields.
141
+ But it is limited to fields with the same dtype as unstructured numpy arrays
142
+ only contain one dtype.
118
143
119
- def read_points_list (cloud , field_names = None , skip_nans = False , uvs = []):
144
+ :param cloud: The point cloud to read from sensor_msgs.PointCloud2.
145
+ :param field_names: The names of fields to read. If None, read all fields.
146
+ (Type: Iterable, Default: None)
147
+ :param skip_nans: If True, then don't return any point with a NaN value.
148
+ (Type: Bool, Default: False)
149
+ :param uvs: If specified, then only return the points at the given
150
+ coordinates. (Type: Iterable, Default: None)
151
+ :param reshape_organized_cloud: Returns the array as an 2D organized point cloud if set.
152
+ :return: Numpy array containing all points.
153
+ """
154
+ assert all (cloud .fields [0 ].datatype == field .datatype for field in cloud .fields [1 :]), \
155
+ 'All fields need to have the same datatype. Use `read_points()` otherwise.'
156
+ structured_numpy_array = read_points (
157
+ cloud , field_names , skip_nans , uvs , reshape_organized_cloud )
158
+ return structured_to_unstructured (structured_numpy_array )
159
+
160
+
161
+ def read_points_list (
162
+ cloud : PointCloud2 ,
163
+ field_names : Optional [List [str ]] = None ,
164
+ skip_nans : bool = False ,
165
+ uvs : Optional [Iterable ] = None ) -> List [NamedTuple ]:
120
166
"""
121
167
Read points from a sensor_msgs.PointCloud2 message.
122
168
@@ -129,7 +175,7 @@ def read_points_list(cloud, field_names=None, skip_nans=False, uvs=[]):
129
175
:param skip_nans: If True, then don't return any point with a NaN value.
130
176
(Type: Bool, Default: False)
131
177
:param uvs: If specified, then only return the points at the given
132
- coordinates. (Type: Iterable, Default: empty list ]
178
+ coordinates. (Type: Iterable, Default: None ]
133
179
:return: List of namedtuples containing the values for each point
134
180
"""
135
181
assert isinstance (cloud , PointCloud2 ), \
@@ -144,7 +190,53 @@ def read_points_list(cloud, field_names=None, skip_nans=False, uvs=[]):
144
190
skip_nans , uvs )]
145
191
146
192
147
- def create_cloud (header , fields , points ):
193
+ def dtype_from_fields (fields : Iterable [PointField ]) -> np .dtype :
194
+ """
195
+ Convert a Iterable of sensor_msgs.msg.PointField messages to a np.dtype.
196
+
197
+ :param fields: The point cloud fields.
198
+ (Type: iterable of sensor_msgs.msg.PointField)
199
+ :returns: NumPy datatype
200
+ """
201
+ # Create a lists containing the names, offsets and datatypes of all fields
202
+ field_names = []
203
+ field_offsets = []
204
+ field_datatypes = []
205
+ for i , field in enumerate (fields ):
206
+ # Datatype as numpy datatype
207
+ datatype = _DATATYPES [field .datatype ]
208
+ # Name field
209
+ if field .name == '' :
210
+ name = f'{ DUMMY_FIELD_PREFIX } _{ i } '
211
+ else :
212
+ name = field .name
213
+ # Handle fields with count > 1 by creating subfields with a suffix consiting
214
+ # of "_" followed by the subfield counter [0 -> (count - 1)]
215
+ assert field .count > 0 , "Can't process fields with count = 0."
216
+ for a in range (field .count ):
217
+ # Add suffix if we have multiple subfields
218
+ if field .count > 1 :
219
+ subfield_name = f'{ name } _{ a } '
220
+ else :
221
+ subfield_name = name
222
+ assert subfield_name not in field_names , 'Duplicate field names are not allowed!'
223
+ field_names .append (subfield_name )
224
+ # Create new offset that includes subfields
225
+ field_offsets .append (field .offset + a * datatype .itemsize )
226
+ field_datatypes .append (datatype .str )
227
+
228
+ # Create a tuple for each field containing name and data type
229
+ return np .dtype ({
230
+ 'names' : field_names ,
231
+ 'formats' : field_datatypes ,
232
+ 'offsets' : field_offsets ,
233
+ })
234
+
235
+
236
+ def create_cloud (
237
+ header : Header ,
238
+ fields : Iterable [PointField ],
239
+ points : Iterable ) -> PointCloud2 :
148
240
"""
149
241
Create a sensor_msgs.msg.PointCloud2 message.
150
242
@@ -157,28 +249,61 @@ def create_cloud(header, fields, points):
157
249
the fields parameter)
158
250
:return: The point cloud as sensor_msgs.msg.PointCloud2
159
251
"""
160
- cloud_struct = struct .Struct (_get_struct_fmt (False , fields ))
161
-
162
- buff = ctypes .create_string_buffer (cloud_struct .size * len (points ))
163
-
164
- point_step , pack_into = cloud_struct .size , cloud_struct .pack_into
165
- offset = 0
166
- for p in points :
167
- pack_into (buff , offset , * p )
168
- offset += point_step
169
-
170
- return PointCloud2 (header = header ,
171
- height = 1 ,
172
- width = len (points ),
173
- is_dense = False ,
174
- is_bigendian = False ,
175
- fields = fields ,
176
- point_step = cloud_struct .size ,
177
- row_step = cloud_struct .size * len (points ),
178
- data = buff .raw )
179
-
180
-
181
- def create_cloud_xyz32 (header , points ):
252
+ # Check if input is numpy array
253
+ if isinstance (points , np .ndarray ):
254
+ # Check if this is an unstructured array
255
+ if points .dtype .names is None :
256
+ assert all (fields [0 ].datatype == field .datatype for field in fields [1 :]), \
257
+ 'All fields need to have the same datatype. Pass a structured NumPy array \
258
+ with multiple dtypes otherwise.'
259
+ # Convert unstructured to structured array
260
+ points = unstructured_to_structured (
261
+ points ,
262
+ dtype = dtype_from_fields (fields ))
263
+ else :
264
+ assert points .dtype == dtype_from_fields (fields ), \
265
+ 'PointFields and structured NumPy array dtype do not match for all fields! \
266
+ Check their field order, names and types.'
267
+ else :
268
+ # Cast python objects to structured NumPy array (slow)
269
+ points = np .array (
270
+ # Points need to be tuples in the structured array
271
+ list (map (tuple , points )),
272
+ dtype = dtype_from_fields (fields ))
273
+
274
+ # Handle organized clouds
275
+ assert len (points .shape ) <= 2 , \
276
+ 'Too many dimensions for organized cloud! \
277
+ Points can only be organized in max. two dimensional space'
278
+ height = 1
279
+ width = points .shape [0 ]
280
+ # Check if input points are an organized cloud (2D array of points)
281
+ if len (points .shape ) == 2 :
282
+ height = points .shape [1 ]
283
+
284
+ # Convert numpy points to array.array
285
+ memory_view = memoryview (points )
286
+ casted = memory_view .cast ('B' )
287
+ array_array = array .array ('B' )
288
+ array_array .frombytes (casted )
289
+
290
+ # Put everything together
291
+ cloud = PointCloud2 (
292
+ header = header ,
293
+ height = height ,
294
+ width = width ,
295
+ is_dense = False ,
296
+ is_bigendian = sys .byteorder != 'little' ,
297
+ fields = fields ,
298
+ point_step = points .dtype .itemsize ,
299
+ row_step = (points .dtype .itemsize * width ))
300
+ # Set cloud via property instead of the constructor because of the bug described in
301
+ # https://github.com/ros2/common_interfaces/issues/176
302
+ cloud .data = array_array
303
+ return cloud
304
+
305
+
306
+ def create_cloud_xyz32 (header : Header , points : Iterable ) -> PointCloud2 :
182
307
"""
183
308
Create a sensor_msgs.msg.PointCloud2 message with (x, y, z) fields.
184
309
@@ -193,23 +318,3 @@ def create_cloud_xyz32(header, points):
193
318
PointField (name = 'z' , offset = 8 ,
194
319
datatype = PointField .FLOAT32 , count = 1 )]
195
320
return create_cloud (header , fields , points )
196
-
197
-
198
- def _get_struct_fmt (is_bigendian , fields , field_names = None ):
199
- fmt = '>' if is_bigendian else '<'
200
-
201
- offset = 0
202
- for field in (f for f in sorted (fields , key = lambda f : f .offset )
203
- if field_names is None or f .name in field_names ):
204
- if offset < field .offset :
205
- fmt += 'x' * (field .offset - offset )
206
- offset = field .offset
207
- if field .datatype not in _DATATYPES :
208
- print ('Skipping unknown PointField datatype [%d]' %
209
- field .datatype , file = sys .stderr )
210
- else :
211
- datatype_fmt , datatype_length = _DATATYPES [field .datatype ]
212
- fmt += field .count * datatype_fmt
213
- offset += field .count * datatype_length
214
-
215
- return fmt
0 commit comments