test_rgbd_launch.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 #***********************************************************
4 #* Software License Agreement (BSD License)
5 #*
6 #* Copyright (c) 2009, Willow Garage, Inc.
7 #* All rights reserved.
8 #*
9 #* Redistribution and use in source and binary forms, with or without
10 #* modification, are permitted provided that the following conditions
11 #* are met:
12 #*
13 #* * Redistributions of source code must retain the above copyright
14 #* notice, this list of conditions and the following disclaimer.
15 #* * Redistributions in binary form must reproduce the above
16 #* copyright notice, this list of conditions and the following
17 #* disclaimer in the documentation and/or other materials provided
18 #* with the distribution.
19 #* * Neither the name of the Willow Garage nor the names of its
20 #* contributors may be used to endorse or promote products derived
21 #* from this software without specific prior written permission.
22 #*
23 #* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 #* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 #* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 #* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 #* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 #* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 #* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 #* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 #* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 #* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 #* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 #* POSSIBILITY OF SUCH DAMAGE.
35 #***********************************************************
36 # Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
37 
38 
39 import tf2_ros
40 import rospy
41 from unittest import TestCase
42 
43 
44 class TestRGBDLaunch(TestCase):
45  def testKinectFrames(self):
46  tfBuffer = tf2_ros.Buffer()
47  tfListener = tf2_ros.TransformListener(tfBuffer)
48  try:
49  trans = tfBuffer.lookup_transform("camera_depth_optical_frame",
50  "camera_rgb_optical_frame",
51  rospy.Time(),
52  timeout=rospy.Duration(20))
53  self.assertIsNotNone(trans)
54  except Exception as e:
55  self.fail(str(e))
56 
57 if __name__ == '__main__':
58  rospy.init_node("test_kinect_frames")
59  import rostest
60  rostest.rosrun("rgbd_launch", "test_kinect_frames", TestRGBDLaunch)


rgbd_launch
Author(s): Patrick Mihelich and others
autogenerated on Mon Jun 10 2019 14:37:47