enumerants.py
Go to the documentation of this file.
00001 import roslib
00002 roslib.load_manifest('opencv_tests')
00003 import rostest
00004 import rospy
00005 import unittest
00006 
00007 import sensor_msgs.msg
00008 import cv
00009 
00010 from cv_bridge import CvBridge, CvBridgeError
00011 
00012 class TestEnumerants(unittest.TestCase):
00013 
00014     def test_enumerants(self):
00015 
00016         img_msg = sensor_msgs.msg.Image()
00017         img_msg.width = 640
00018         img_msg.height = 480
00019         img_msg.encoding = "rgba8"
00020         img_msg.step = 640*4
00021         img_msg.data = (640 * 480) * "1234"
00022 
00023         bridge_ = CvBridge()
00024         cvim = bridge_.imgmsg_to_cv(img_msg, "rgb8")
00025 
00026         # A 3 channel image cannot be sent as an rgba8
00027         self.assertRaises(CvBridgeError, lambda: bridge_.cv_to_imgmsg(cvim, "rgba8"))
00028 
00029         # but it can be sent as rgb8 and bgr8
00030         bridge_.cv_to_imgmsg(cvim, "rgb8")
00031         bridge_.cv_to_imgmsg(cvim, "bgr8")
00032 
00033     def test_encode_decode(self):
00034         fmts = [ cv.IPL_DEPTH_8U, cv.IPL_DEPTH_8S, cv.IPL_DEPTH_16U, cv.IPL_DEPTH_16S, cv.IPL_DEPTH_32S, cv.IPL_DEPTH_32F, cv.IPL_DEPTH_64F ]
00035 
00036         cvb_en = CvBridge()
00037         cvb_de = CvBridge()
00038 
00039         for w in range(100, 800, 100):
00040             for h in range(100, 800, 100):
00041                 for f in  [ cv.IPL_DEPTH_8U ]:
00042                     for channels in (1,2,3,4):
00043                         original = cv.CreateImage((w, h), f, channels)
00044                         cv.Set(original, (1,2,3,4));
00045                         rosmsg = cvb_en.cv_to_imgmsg(original)
00046                         newimg = cvb_de.imgmsg_to_cv(rosmsg)
00047                         self.assert_(cv.GetElemType(original) == cv.GetElemType(newimg))
00048                         self.assert_(cv.GetSize(original) == cv.GetSize(newimg))
00049                         self.assert_(len(original.tostring()) == len(newimg.tostring()))
00050 
00051     def test_mono16(self):
00052         br = CvBridge()
00053         im = cv.CreateImage((640, 480), 8, 3)
00054         msg = br.cv_to_imgmsg(im)
00055 
00056 if __name__ == '__main__':
00057   if 1:
00058     rostest.unitrun('opencv_tests', 'enumerants', TestEnumerants)
00059   else:
00060     suite = unittest.TestSuite()
00061     suite.addTest(TestEnumerants('test_mono16'))
00062     unittest.TextTestRunner(verbosity=2).run(suite)


opencv_tests
Author(s): James Bowman
autogenerated on Sat Dec 28 2013 17:53:20