00001 import sys
00002
00003 from .registry import converts_from_numpy, converts_to_numpy
00004 from sensor_msgs.msg import Image
00005
00006 import numpy as np
00007 from numpy.lib.stride_tricks import as_strided
00008
00009 name_to_dtypes = {
00010 "rgb8": (np.uint8, 3),
00011 "rgba8": (np.uint8, 4),
00012 "rgb16": (np.uint16, 3),
00013 "rgba16": (np.uint16, 4),
00014 "bgr8": (np.uint8, 3),
00015 "bgra8": (np.uint8, 4),
00016 "bgr16": (np.uint16, 3),
00017 "bgra16": (np.uint16, 4),
00018 "mono8": (np.uint8, 1),
00019 "mono16": (np.uint16, 1),
00020
00021
00022 "bayer_rggb8": (np.uint8, 1),
00023 "bayer_bggr8": (np.uint8, 1),
00024 "bayer_gbrg8": (np.uint8, 1),
00025 "bayer_grbg8": (np.uint8, 1),
00026 "bayer_rggb16": (np.uint16, 1),
00027 "bayer_bggr16": (np.uint16, 1),
00028 "bayer_gbrg16": (np.uint16, 1),
00029 "bayer_grbg16": (np.uint16, 1),
00030
00031
00032 "8UC1": (np.uint8, 1),
00033 "8UC2": (np.uint8, 2),
00034 "8UC3": (np.uint8, 3),
00035 "8UC4": (np.uint8, 4),
00036 "8SC1": (np.int8, 1),
00037 "8SC2": (np.int8, 2),
00038 "8SC3": (np.int8, 3),
00039 "8SC4": (np.int8, 4),
00040 "16UC1": (np.int16, 1),
00041 "16UC2": (np.int16, 2),
00042 "16UC3": (np.int16, 3),
00043 "16UC4": (np.int16, 4),
00044 "16SC1": (np.uint16, 1),
00045 "16SC2": (np.uint16, 2),
00046 "16SC3": (np.uint16, 3),
00047 "16SC4": (np.uint16, 4),
00048 "32SC1": (np.int32, 1),
00049 "32SC2": (np.int32, 2),
00050 "32SC3": (np.int32, 3),
00051 "32SC4": (np.int32, 4),
00052 "32FC1": (np.float32, 1),
00053 "32FC2": (np.float32, 2),
00054 "32FC3": (np.float32, 3),
00055 "32FC4": (np.float32, 4),
00056 "64FC1": (np.float64, 1),
00057 "64FC2": (np.float64, 2),
00058 "64FC3": (np.float64, 3),
00059 "64FC4": (np.float64, 4)
00060 }
00061
00062 @converts_to_numpy(Image)
00063 def image_to_numpy(msg):
00064 if not msg.encoding in name_to_dtypes:
00065 raise TypeError('Unrecognized encoding {}'.format(msg.encoding))
00066
00067 dtype_class, channels = name_to_dtypes[msg.encoding]
00068 dtype = np.dtype(dtype_class)
00069 dtype = dtype.newbyteorder('>' if msg.is_bigendian else '<')
00070 shape = (msg.height, msg.width, channels)
00071
00072 data = np.fromstring(msg.data, dtype=dtype).reshape(shape)
00073 data.strides = (
00074 msg.step,
00075 dtype.itemsize * channels,
00076 dtype.itemsize
00077 )
00078
00079 if channels == 1:
00080 data = data[...,0]
00081 return data
00082
00083
00084 @converts_from_numpy(Image)
00085 def numpy_to_image(arr, encoding):
00086 if not encoding in name_to_dtypes:
00087 raise TypeError('Unrecognized encoding {}'.format(encoding))
00088
00089 im = Image(encoding=encoding)
00090
00091
00092 dtype_class, exp_channels = name_to_dtypes[encoding]
00093 dtype = np.dtype(dtype_class)
00094 if len(arr.shape) == 2:
00095 im.height, im.width, channels = arr.shape + (1,)
00096 elif len(arr.shape) == 3:
00097 im.height, im.width, channels = arr.shape
00098 else:
00099 raise TypeError("Array must be two or three dimensional")
00100
00101
00102 if exp_channels != channels:
00103 raise TypeError("Array has {} channels, {} requires {}".format(
00104 channels, encoding, exp_channels
00105 ))
00106 if dtype_class != arr.dtype.type:
00107 raise TypeError("Array is {}, {} requires {}".format(
00108 arr.dtype.type, encoding, dtype_class
00109 ))
00110
00111
00112 contig = np.ascontiguousarray(arr)
00113 im.data = contig.tostring()
00114 im.step = contig.strides[0]
00115 im.is_bigendian = (
00116 arr.dtype.byteorder == '>' or
00117 arr.dtype.byteorder == '=' and sys.byteorder == 'big'
00118 )
00119
00120 return im