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     head_track_node.py - Version 1.0 2010-12-28
00036 """
00037 
00038 import roslib; roslib.load_manifest('pi_head_tracking_tutorial')
00039 import rospy
00040 from sensor_msgs.msg import JointState, RegionOfInterest, CameraInfo
00041 from math import radians
00042 
00043 class head_track():
00044     def __init__(self):
00045         rospy.init_node("head_track")
00046         rospy.on_shutdown(self.shutdown)
00047         
00048         """ Publish the movement commands on the /cmd_joints topic using the 
00049             JointState message type. """
00050         self.head_pub = rospy.Publisher("/cmd_joints", JointState)
00051         
00052         self.rate = rospy.get_param("~rate", 10)
00053         
00054         """ The pan/tilt thresholds indicate how many pixels the ROI needs to be off-center
00055             before we make a movement. """
00056         self.pan_threshold = int(rospy.get_param("~pan_threshold", 5))
00057         self.tilt_threshold = int(rospy.get_param("~tilt_threshold", 5))
00058         
00059         """ The k_pan and k_tilt parameter determine how responsive the servo movements are.
00060             If these are set too high, oscillation can result. """
00061         self.k_pan = rospy.get_param("~k_pan", 7.0)
00062         self.k_tilt = rospy.get_param("~k_tilt", 5.0)
00063         
00064         self.max_pan = rospy.get_param("~max_pan", radians(145))
00065         self.min_pan = rospy.get_param("~min_pan", radians(-145))
00066         self.max_tilt = rospy.get_param("~max_tilt", radians(90))
00067         self.min_tilt = rospy.get_param("~min_tilt", radians(-90))
00068         
00069         r = rospy.Rate(self.rate) 
00070         
00071         self.head_cmd = JointState()
00072         self.joints = ["head_pan_joint", "head_tilt_joint"]
00073         self.head_cmd.name = self.joints
00074         self.head_cmd.position = [0, 0]
00075         self.head_cmd.velocity = [1, 1]
00076         self.head_cmd.header.stamp = rospy.Time.now()
00077         self.head_cmd.header.frame_id = 'head_pan_joint'
00078     
00079         """ Center the head and pan servos at the start. """
00080         for i in range(3):
00081             self.head_pub.publish(self.head_cmd)
00082             rospy.sleep(1)
00083         
00084         self.tracking_seq = 0
00085         self.last_tracking_seq = -1
00086         
00087         rospy.Subscriber('roi', RegionOfInterest, self.setPanTiltSpeeds)
00088         rospy.Subscriber('camera_info', CameraInfo, self.getCameraInfo)
00089         
00090         while not rospy.is_shutdown():
00091             """ Publish the pan/tilt movement commands. """
00092             self.head_cmd.header.stamp = rospy.Time.now()
00093             self.head_cmd.header.frame_id = 'head_pan_joint'
00094             if self.last_tracking_seq == self.tracking_seq:
00095                 self.head_cmd.velocity = [0.0001, 0.0001]
00096             else:
00097                 self.last_tracking_seq = self.tracking_seq
00098             self.head_pub.publish(self.head_cmd)
00099             r.sleep()
00100     
00101     def setPanTiltSpeeds(self, msg):
00102         """ When OpenCV loses the ROI, the message stops updating.  Use this counter to
00103             determine when it stops. """
00104         self.tracking_seq += 1
00105         
00106         """ Check to see if we have lost the ROI. """
00107         if msg.width == 0 or msg.height == 0 or msg.width > self.image_width / 2 or \
00108                 msg.height > self.image_height / 2:
00109             self.head_cmd.velocity = [0, 0]
00110             return
00111 
00112         """ Compute the center of the ROI """
00113         COG_x = msg.x_offset + msg.width / 2 - self.image_width / 2
00114         COG_y = msg.y_offset + msg.height / 2 - self.image_height / 2
00115           
00116         """ Pan the camera only if the displacement of the COG exceeds the threshold. """
00117         if abs(COG_x) > self.pan_threshold:
00118             """ Set the pan speed proportion to the displacement of the horizontal displacement
00119                 of the target. """
00120             self.head_cmd.velocity[0] = self.k_pan * abs(COG_x) / float(self.image_width)
00121                
00122             """ Set the target position to one of the min or max positions--we'll never
00123                 get there since we are tracking using speed. """
00124             if COG_x > 0:
00125                 self.head_cmd.position[0] = self.min_pan
00126             else:
00127                 self.head_cmd.position[0] = self.max_pan
00128         else:
00129             self.head_cmd.velocity[0] = 0.0001
00130         
00131         """ Tilt the camera only if the displacement of the COG exceeds the threshold. """
00132         if abs(COG_y) > self.tilt_threshold:
00133             """ Set the tilt speed proportion to the displacement of the vertical displacement
00134                 of the target. """
00135             self.head_cmd.velocity[1] = self.k_tilt * abs(COG_y) / float(self.image_height)
00136             
00137             """ Set the target position to one of the min or max positions--we'll never
00138                 get there since we are tracking using speed. """
00139             if COG_y < 0:
00140                 self.head_cmd.position[1] = self.min_tilt
00141             else:
00142                 self.head_cmd.position[1] = self.max_tilt
00143         else:
00144             self.head_cmd.velocity[1] = 0.0001
00145             
00146     def getCameraInfo(self, msg):
00147         self.image_width = msg.width
00148         self.image_height = msg.height
00149         
00150     def shutdown(self):
00151         rospy.loginfo("Shutting down head tracking node...")         
00152                    
00153 if __name__ == '__main__':
00154     try:
00155         head_track()
00156     except rospy.ROSInterruptException:
00157         rospy.loginfo("Head tracking node is shut down.")
00158 
00159 
00160 
00161