35 Functions for working with PointCloud2. 38 __docformat__ =
"restructuredtext en" 40 from .registry
import converts_from_numpy, converts_to_numpy
43 from sensor_msgs.msg
import PointCloud2, PointField
47 DUMMY_FIELD_PREFIX =
'__' 50 type_mappings = [(PointField.INT8, np.dtype(
'int8')), (PointField.UINT8, np.dtype(
'uint8')), (PointField.INT16, np.dtype(
'int16')),
51 (PointField.UINT16, np.dtype(
'uint16')), (PointField.INT32, np.dtype(
'int32')), (PointField.UINT32, np.dtype(
'uint32')),
52 (PointField.FLOAT32, np.dtype(
'float32')), (PointField.FLOAT64, np.dtype(
'float64'))]
53 pftype_to_nptype = dict(type_mappings)
54 nptype_to_pftype = dict((nptype, pftype)
for pftype, nptype
in type_mappings)
57 pftype_sizes = {PointField.INT8: 1, PointField.UINT8: 1, PointField.INT16: 2, PointField.UINT16: 2,
58 PointField.INT32: 4, PointField.UINT32: 4, PointField.FLOAT32: 4, PointField.FLOAT64: 8}
62 '''Convert a list of PointFields to a numpy record datatype. 67 while offset < f.offset:
69 np_dtype_list.append((
'%s%d' % (DUMMY_FIELD_PREFIX, offset), np.uint8))
72 dtype = pftype_to_nptype[f.datatype]
74 dtype = np.dtype((dtype, f.count))
76 np_dtype_list.append((f.name, dtype))
77 offset += pftype_sizes[f.datatype] * f.count
80 while offset < point_step:
81 np_dtype_list.append((
'%s%d' % (DUMMY_FIELD_PREFIX, offset), np.uint8))
89 '''Convert a numpy record datatype into a list of PointFields. 92 for field_name
in dtype.names:
93 np_field_type, field_offset = dtype.fields[field_name]
96 if np_field_type.subdtype:
97 item_dtype, shape = np_field_type.subdtype
98 pf.count = np.prod(shape)
99 np_field_type = item_dtype
103 pf.datatype = nptype_to_pftype[np_field_type]
104 pf.offset = field_offset
110 ''' Converts a rospy PointCloud2 message to a numpy recordarray 112 Reshapes the returned array to have shape (height, width), even if the height is 1. 114 The reason for using np.frombuffer rather than struct.unpack is speed... especially 115 for large point clouds, this will be <much> faster. 121 cloud_arr = np.frombuffer(cloud_msg.data, dtype_list)
124 cloud_arr = cloud_arr[
125 [fname
for fname, _type
in dtype_list
if not (fname[:len(DUMMY_FIELD_PREFIX)] == DUMMY_FIELD_PREFIX)]]
127 if squeeze
and cloud_msg.height == 1:
128 return np.reshape(cloud_arr, (cloud_msg.width,))
130 return np.reshape(cloud_arr, (cloud_msg.height, cloud_msg.width))
134 '''Converts a numpy record array to a sensor_msgs.msg.PointCloud2. 137 cloud_arr = np.atleast_2d(cloud_arr)
139 cloud_msg = PointCloud2()
141 if stamp
is not None:
142 cloud_msg.header.stamp = stamp
143 if frame_id
is not None:
144 cloud_msg.header.frame_id = frame_id
145 cloud_msg.height = cloud_arr.shape[0]
146 cloud_msg.width = cloud_arr.shape[1]
148 cloud_msg.is_bigendian =
False 149 cloud_msg.point_step = cloud_arr.dtype.itemsize
150 cloud_msg.row_step = cloud_msg.point_step*cloud_arr.shape[1]
151 cloud_msg.is_dense = all([np.isfinite(cloud_arr[fname]).all()
for fname
in cloud_arr.dtype.names])
152 cloud_msg.data = cloud_arr.tostring()
156 '''Takes an array with named np.uint8 fields 'r', 'g', and 'b', and returns an array in
157 which they have been merged into a single np.float32 'rgb' field. The first byte of this
158 field is the '
r' uint8, the second is the 'g', uint8, and the third is the 'b' uint8.
160 This is the way that pcl likes to handle RGB colors for some reason.
162 r = np.asarray(cloud_arr['
r'], dtype=np.uint32) 163 g = np.asarray(cloud_arr['g'], dtype=np.uint32)
164 b = np.asarray(cloud_arr[
'b'], dtype=np.uint32)
165 rgb_arr = np.array((r << 16) | (g << 8) | (b << 0), dtype=np.uint32)
169 rgb_arr.dtype = np.float32
173 for field_name
in cloud_arr.dtype.names:
174 field_type, field_offset = cloud_arr.dtype.fields[field_name]
175 if field_name
not in (
'r', 'g', 'b'):
176 new_dtype.append((field_name, field_type))
177 new_dtype.append((
'rgb', np.float32))
178 new_cloud_arr = np.zeros(cloud_arr.shape, new_dtype)
181 for field_name
in new_cloud_arr.dtype.names:
182 if field_name ==
'rgb':
183 new_cloud_arr[field_name] = rgb_arr
185 new_cloud_arr[field_name] = cloud_arr[field_name]
190 '''Takes an array with a named 'rgb' float32 field, and returns an array in which 191 this has been split into 3 uint 8 fields: 'r', 'g', and 'b'.
193 (pcl stores rgb in packed 32 bit floats)
195 rgb_arr = cloud_arr['rgb'].copy()
196 rgb_arr.dtype = np.uint32
197 r = np.asarray((rgb_arr >> 16) & 255, dtype=np.uint8)
198 g = np.asarray((rgb_arr >> 8) & 255, dtype=np.uint8)
199 b = np.asarray(rgb_arr & 255, dtype=np.uint8)
201 # create a new array, without rgb, but with r, g, and b fields
203 for field_name in cloud_arr.dtype.names:
204 field_type, field_offset = cloud_arr.dtype.fields[field_name]
205 if not field_name == 'rgb':
206 new_dtype.append((field_name, field_type))
207 new_dtype.append(('
r', np.uint8)) 208 new_dtype.append(('g', np.uint8))
209 new_dtype.append((
'b', np.uint8))
210 new_cloud_arr = np.zeros(cloud_arr.shape, new_dtype)
213 for field_name
in new_cloud_arr.dtype.names:
214 if field_name ==
'r': 215 new_cloud_arr[field_name] = r 216 elif field_name ==
'g':
217 new_cloud_arr[field_name] = g
218 elif field_name ==
'b':
219 new_cloud_arr[field_name] = b
221 new_cloud_arr[field_name] = cloud_arr[field_name]
225 '''Pulls out x, y, and z columns from the cloud recordarray, and returns 230 mask = np.isfinite(cloud_array[
'x']) & np.isfinite(cloud_array[
'y']) & np.isfinite(cloud_array[
'z'])
231 cloud_array = cloud_array[mask]
234 points = np.zeros(cloud_array.shape + (3,), dtype=dtype)
235 points[...,0] = cloud_array[
'x']
236 points[...,1] = cloud_array[
'y']
237 points[...,2] = cloud_array[
'z']
def converts_from_numpy(msgtype, plural=False)
def split_rgb_field(cloud_arr)
def converts_to_numpy(msgtype, plural=False)
def pointcloud2_to_array(cloud_msg, squeeze=True)
def dtype_to_fields(dtype)
def pointcloud2_to_xyz_array(cloud_msg, remove_nans=True)
def fields_to_dtype(fields, point_step)
def array_to_pointcloud2(cloud_arr, stamp=None, frame_id=None)
def get_xyz_points(cloud_array, remove_nans=True, dtype=np.float)
def merge_rgb_fields(cloud_arr)