cap_ground_truth.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 import roslib
00004 roslib.load_manifest('geometry_msgs')
00005 roslib.load_manifest('tf')
00006 import rospy
00007 import tf
00008 from geometry_msgs.msg import PointStamped
00009 
00010 import time
00011 
00012 rospy.init_node('ground_truth_tag_pose')
00013 listener = tf.TransformListener()
00014 
00015 
00016 # listener.waitForTransform('/l_gripper_tool_frame', '/ear_antenna_left',
00017 #                           rospy.Time(0), timeout = rospy.Duration(10) )
00018 listener.waitForTransform('/l_gripper_tool_frame', '/map',
00019                           rospy.Time(0), timeout = rospy.Duration(10) )
00020 
00021 rate = rospy.Rate(2)
00022 while not rospy.is_shutdown():
00023     p = PointStamped()
00024     p.header.stamp = rospy.Time(0)
00025     p.header.frame_id =  '/l_gripper_tool_frame'
00026     p.point.x = 0.015 # Frame is actually in middle of fingers.  Move it out to tips
00027     #p_earl = listener.transformPoint('/ear_antenna_left', p)
00028     p_earl = listener.transformPoint('/map', p)
00029     print '<x,y,z> = <%2.3f, %2.3f, %2.3f> ' % ( p_earl.point.x, p_earl.point.y, p_earl.point.z )
00030 
00031     rate.sleep()


rfid_datacapture
Author(s): Travis Deyle
autogenerated on Wed Nov 27 2013 12:11:16