Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import roslib; roslib.load_manifest('pi_head_tracking_3d_part1')
00036 import rospy
00037 import tf
00038 from geometry_msgs.msg import PointStamped
00039 from std_msgs.msg import Float64
00040
00041 import math
00042
00043 class PointHeadNode():
00044
00045 def __init__(self):
00046
00047 rospy.init_node('point_head_node', anonymous=True)
00048
00049 dynamixel_namespace = rospy.get_namespace()
00050 rate = rospy.get_param('~rate', 1)
00051 r = rospy.Rate(rate)
00052
00053
00054 self.target_point = PointStamped()
00055 self.last_target_point = PointStamped()
00056
00057
00058 rospy.Subscriber('/target_point', PointStamped, self.update_target_point)
00059
00060
00061 self.head_pan_frame = 'head_pan_link'
00062 self.head_pan_pub = rospy.Publisher(dynamixel_namespace + 'head_pan_controller/command', Float64)
00063
00064
00065 self.head_tilt_frame = 'head_tilt_link'
00066 self.head_tilt_pub = rospy.Publisher(dynamixel_namespace + 'head_tilt_controller/command', Float64)
00067
00068
00069 self.tf = tf.TransformListener()
00070
00071
00072 self.tf.waitForTransform(self.head_pan_frame, self.head_tilt_frame, rospy.Time(), rospy.Duration(5.0))
00073
00074
00075 rospy.sleep(1)
00076 self.center_head()
00077
00078 rospy.loginfo("Ready to accept target point")
00079
00080 while not rospy.is_shutdown():
00081 rospy.wait_for_message('/target_point', PointStamped)
00082 if self.target_point == self.last_target_point:
00083 continue
00084 try:
00085 target_angles = self.transform_target_point(self.target_point)
00086 except (tf.Exception, tf.ConnectivityException, tf.LookupException):
00087 rospy.logerr("tf Failure")
00088 continue
00089
00090 self.head_pan_pub.publish(target_angles[0])
00091 self.head_tilt_pub.publish(target_angles[1])
00092
00093 self.last_target_point = self.target_point
00094 rospy.loginfo("Setting Target Point:\n" + str(self.target_point))
00095
00096 r.sleep()
00097
00098 def update_target_point(self, msg):
00099 self.target_point = msg
00100
00101 def center_head(self):
00102 self.head_pan_pub.publish(0.0)
00103 self.head_tilt_pub.publish(0.0)
00104 rospy.sleep(3)
00105
00106 def transform_target_point(self, target):
00107
00108 pan_ref_frame = self.head_pan_frame
00109 tilt_ref_frame = self.head_tilt_frame
00110
00111
00112 self.tf.waitForTransform(pan_ref_frame, target.header.frame_id, rospy.Time(), rospy.Duration(5.0))
00113 self.tf.waitForTransform(tilt_ref_frame, target.header.frame_id, rospy.Time(), rospy.Duration(5.0))
00114
00115
00116 pan_target = self.tf.transformPoint(pan_ref_frame, target)
00117 pan_angle = math.atan2(pan_target.point.y, pan_target.point.x)
00118
00119
00120 tilt_target = self.tf.transformPoint(tilt_ref_frame, target)
00121 tilt_angle = math.atan2(tilt_target.point.z,
00122 math.sqrt(math.pow(tilt_target.point.x, 2) + math.pow(tilt_target.point.y, 2)))
00123
00124 return [pan_angle, tilt_angle]
00125
00126 if __name__ == '__main__':
00127 try:
00128 point_head = PointHeadNode()
00129 rospy.spin()
00130 except rospy.ROSInterruptException:
00131 pass
00132