Go to the documentation of this file.00001
00002 import roslib
00003 roslib.load_manifest('ar_kinect')
00004 from geometry_msgs.msg import Pose2D, PoseStamped, Pose
00005 from ar_pose.msg import ARMarkers
00006 from tf import TransformListener
00007 from math import cos, sin, pi
00008
00009 import rospy
00010 import tf
00011 from std_msgs.msg import Float64
00012
00013 data = ARMarkers()
00014 angle = 0.0
00015
00016 def callback(data):
00017 global angle
00018 angle = data.data
00019
00020
00021 if __name__ == '__main__':
00022 rospy.init_node('kinect_transform_publisher')
00023
00024
00025
00026 rospy.Subscriber('cur_tilt_angle', Float64, callback)
00027
00028
00029
00030 pub2 = rospy.Publisher('tilt_angle', Float64)
00031
00032
00033 br = tf.TransformBroadcaster()
00034
00035 rate = rospy.Rate(10.0)
00036
00037 while not rospy.is_shutdown():
00038
00039
00040 pub2.publish(-52.0)
00041 stageAngle = 45
00042 x = 0.035 - 0.002315 + 0.025*sin(-52*pi/180)
00043 y = 0
00044 z = 0.0062 + 0.0932 + 0.02315 + 0.025*cos(-52*pi/180)
00045
00046 now = rospy.Time.now()
00047 br.sendTransform((x, y, z), tf.transformations.quaternion_from_euler(0, 52*pi/180, 0),
00048 now, "camera_link","gaze")
00049
00050 rate.sleep()
00051
00052
00053