$search
00001 #! /usr/bin/env python 00002 00003 # Copyright (c) 2010, Arizona Robotics Research Group, University of Arizona 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions are met: 00008 # 00009 # * Redistributions of source code must retain the above copyright 00010 # notice, this list of conditions and the following disclaimer. 00011 # * Redistributions in binary form must reproduce the above copyright 00012 # notice, this list of conditions and the following disclaimer in the 00013 # documentation and/or other materials provided with the distribution. 00014 # * Neither the name of the Willow Garage, Inc. nor the names of its 00015 # contributors may be used to endorse or promote products derived from 00016 # this software without specific prior written permission. 00017 # 00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' 00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 # POSSIBILITY OF SUCH DAMAGE. 00029 00030 # Author: Anh Tran 00031 00032 # Based on the wubble_head_action.py script by Anh Tran. Modifications made by Patrick Goebel 00033 # for the Pi Robot Project. 00034 00035 import roslib; roslib.load_manifest('pi_head_tracking_3d_part2') 00036 import rospy 00037 import tf 00038 from geometry_msgs.msg import PointStamped 00039 from std_msgs.msg import Float64 00040 from dynamixel_controllers.srv import * 00041 00042 import math 00043 00044 class PointHead(): 00045 00046 def __init__(self): 00047 # Initialize new node 00048 rospy.init_node('point_head_node', anonymous=True) 00049 00050 rospy.on_shutdown(self.shutdown) 00051 00052 rate = rospy.get_param('~rate', 20) 00053 self.default_joint_speed = rospy.get_param('~default_joint_speed', 0.6) 00054 r = rospy.Rate(rate) 00055 00056 dynamixels = rospy.get_param('dynamixels', '') 00057 00058 # Remap these in the launch file or command line if necessary 00059 self.camera_link = 'kinect_link' 00060 self.head_pan_joint = 'head_pan_joint' 00061 self.head_tilt_joint = 'head_tilt_joint' 00062 self.head_pan_link = 'head_pan_link' 00063 self.head_tilt_link = 'head_tilt_link' 00064 00065 self.servo_speed = dict() 00066 self.servo_position = dict() 00067 self.torque_enable = dict() 00068 00069 """ Connect to the set_speed and torque_enable services for each servo. 00070 Also define a position publisher for each servo. """ 00071 for name in sorted(dynamixels): 00072 try: 00073 controller = name.replace("_joint", "") + "_controller" 00074 00075 # The set_speed services 00076 set_speed_service = '/' + controller + '/set_speed' 00077 rospy.wait_for_service(set_speed_service) 00078 self.servo_speed[name] = rospy.ServiceProxy(set_speed_service, SetSpeed, persistent=True) 00079 00080 # Initialize the servo speed to the default_joint_speed 00081 self.servo_speed[name](self.default_joint_speed) 00082 00083 # Torque enable/disable control for each servo 00084 torque_service = '/' + controller + '/torque_enable' 00085 rospy.wait_for_service(torque_service) 00086 self.torque_enable[name] = rospy.ServiceProxy(torque_service, TorqueEnable) 00087 00088 # Start each servo in the disabled state so we can move them by hand 00089 self.torque_enable[name](False) 00090 00091 # The position controllers 00092 self.servo_position[name] = rospy.Publisher('/' + controller + '/command', Float64) 00093 except: 00094 rospy.loginfo("Can't contact servo services!") 00095 00096 # Initialize the target point 00097 self.target_point = PointStamped() 00098 self.last_target_point = PointStamped() 00099 00100 # Subscribe to the target_point topic 00101 rospy.Subscriber('/target_point', PointStamped, self.update_target_point) 00102 00103 # Initialize tf listener 00104 self.tf = tf.TransformListener() 00105 00106 # Give the tf buffer a chance to fill up 00107 rospy.sleep(2) 00108 00109 self.tf.waitForTransform(self.camera_link, self.head_pan_link, rospy.Time(), rospy.Duration(1.0)) 00110 00111 # Reset the head position to neutral 00112 rospy.sleep(1) 00113 self.center_head() 00114 00115 rospy.loginfo("Ready to track target point") 00116 00117 while not rospy.is_shutdown(): 00118 rospy.wait_for_message('/target_point', PointStamped) 00119 if self.target_point == self.last_target_point: 00120 continue 00121 try: 00122 target_angles = self.transform_target_point(self.target_point) 00123 except (tf.Exception, tf.ConnectivityException, tf.LookupException): 00124 rospy.logerr("tf Failure") 00125 continue 00126 00127 self.servo_position[self.head_pan_joint].publish(target_angles[0]) 00128 self.servo_position[self.head_tilt_joint].publish(target_angles[1]) 00129 00130 self.last_target_point = self.target_point 00131 00132 r.sleep() 00133 00134 def update_target_point(self, msg): 00135 self.target_point = msg 00136 00137 def center_head(self): 00138 self.servo_position[self.head_pan_joint].publish(0.0) 00139 self.servo_position[self.head_tilt_joint].publish(0.0) 00140 rospy.sleep(3) 00141 00142 def transform_target_point(self, target): 00143 # Wait for tf info (time-out in 5 seconds) 00144 self.tf.waitForTransform(self.head_pan_link, target.header.frame_id, rospy.Time.now(), rospy.Duration(5.0)) 00145 self.tf.waitForTransform(self.head_tilt_link, target.header.frame_id, rospy.Time.now(), rospy.Duration(5.0)) 00146 00147 # Transform target point to pan reference frame & retrieve the pan angle 00148 pan_target = self.tf.transformPoint(self.head_pan_link, target) 00149 pan_angle = math.atan2(pan_target.point.y, pan_target.point.x) 00150 00151 # Transform target point to tilt reference frame & retrieve the tilt angle 00152 tilt_target = self.tf.transformPoint(self.head_tilt_link, target) 00153 tilt_angle = math.atan2(tilt_target.point.z, 00154 math.sqrt(math.pow(tilt_target.point.x, 2) + math.pow(tilt_target.point.y, 2))) 00155 00156 return [pan_angle, tilt_angle] 00157 00158 def shutdown(self): 00159 rospy.loginfo("Shutting down point head node...") 00160 self.center_head() 00161 00162 if __name__ == '__main__': 00163 try: 00164 point_head = PointHead() 00165 rospy.spin() 00166 except rospy.ROSInterruptException: 00167 pass 00168