test_rgbd_launch.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 #***********************************************************
00004 #* Software License Agreement (BSD License)
00005 #*
00006 #*  Copyright (c) 2009, Willow Garage, Inc.
00007 #*  All rights reserved.
00008 #*
00009 #*  Redistribution and use in source and binary forms, with or without
00010 #*  modification, are permitted provided that the following conditions
00011 #*  are met:
00012 #*
00013 #*   * Redistributions of source code must retain the above copyright
00014 #*     notice, this list of conditions and the following disclaimer.
00015 #*   * Redistributions in binary form must reproduce the above
00016 #*     copyright notice, this list of conditions and the following
00017 #*     disclaimer in the documentation and/or other materials provided
00018 #*     with the distribution.
00019 #*   * Neither the name of the Willow Garage nor the names of its
00020 #*     contributors may be used to endorse or promote products derived
00021 #*     from this software without specific prior written permission.
00022 #*
00023 #*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 #*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 #*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 #*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 #*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 #*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 #*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 #*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 #*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 #*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 #*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 #*  POSSIBILITY OF SUCH DAMAGE.
00035 #***********************************************************
00036 # Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
00037 
00038 import tf
00039 import rospy
00040 from unittest import TestCase
00041 
00042 
00043 class TestRGBDLaunch(TestCase):
00044     def testKinectFrames(self):
00045         tfListener = tf.TransformListener()
00046         try:
00047             tfListener.waitForTransform("camera_depth_optical_frame",
00048                                         "camera_rgb_optical_frame",
00049                                         rospy.Time(), rospy.Duration(20))
00050         except Exception as e:
00051             self.fail(str(e))
00052         try:
00053             trans = tfListener.lookupTransform("camera_depth_optical_frame",
00054                                                "camera_rgb_optical_frame",
00055                                                rospy.Time())
00056             self.assertIsNotNone(trans)
00057         except Exception as e:
00058             self.fail(str(e))
00059 
00060 if __name__ == '__main__':
00061     rospy.init_node("test_kinect_frames")
00062     import rostest
00063     rostest.rosrun("rgbd_launch", "test_kinect_frames", TestRGBDLaunch)


rgbd_launch
Author(s): Patrick Mihelich and others
autogenerated on Fri Sep 16 2016 03:22:59