pr2_ar_servo.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 
00003 import numpy as np
00004 import sys
00005 from collections import deque
00006 
00007 import roslib
00008 roslib.load_manifest('hrl_pr2_ar_servo')
00009 
00010 import rospy
00011 from geometry_msgs.msg import Twist
00012 from std_msgs.msg import Float32MultiArray
00013 from visualization_msgs.msg import Marker
00014 from std_msgs.msg import ColorRGBA
00015 
00016 import hrl_geom.transformations as trans
00017 from hrl_geom.pose_converter import PoseConv
00018 from pid_controller import PIDController
00019 from pykdl_utils.joint_kinematics import create_joint_kin
00020 
00021 from ar_pose.msg import ARMarker
00022 
00023 class ServoKalmanFilter(object):
00024     # TODO tune these parameters properly
00025     def __init__(self, delta_t, sigma_z=0.02*0.001, P_init=[0.0, 0.0], sigma_a=0.02):
00026         self.P_init = P_init
00027         self.delta_t = delta_t
00028         self.F = np.mat([[1, delta_t], [0, 1]])
00029         self.Q = np.mat([[delta_t**4/4, delta_t**3/2], [delta_t**3/2, delta_t**2]]) * sigma_a**2
00030         self.H = np.mat([1, 0])
00031         self.R = np.mat([sigma_z])
00032         self.x_cur = None
00033 
00034         self.resid_q_len = int(1./delta_t)
00035         self.resid_sigma_reject = 3.
00036         self.min_reject = 0.1
00037         self.resid_queue = deque()
00038         
00039         self.unreli_q_len = 1 * int(1./delta_t)
00040         self.unreli_queue = deque()
00041         self.unreli_weights = np.linspace(2, 0, self.unreli_q_len)
00042 
00043     def update(self, z_obs, new_obs=True):
00044         is_unreli = False
00045         if new_obs:
00046             if self.x_cur is None:
00047                 self.x_cur = np.mat([z_obs, 0]).T
00048                 self.P_cur = np.mat(np.diag(self.P_init))
00049             # predict
00050             x_pred = self.F * self.x_cur # predicted state
00051             P_pred = self.F * self.P_cur * self.F.T + self.Q # predicted covariance
00052 
00053             # update
00054             y_resi = z_obs - self.H * x_pred # measurement residual
00055             S_resi = self.H * P_pred * self.H.T + self.R # residual covariance
00056             K_gain = P_pred * self.H.T * S_resi**-1 # Kalman gain
00057 
00058             # check residual to be consistent with recent residuals
00059             if (len(self.resid_queue) == self.resid_q_len and
00060                 np.fabs(y_resi) > max(self.min_reject, 
00061                                       self.resid_sigma_reject * np.std(self.resid_queue))):
00062                 # we have determined this observation to be unreliable
00063                 print "INCONSISTENT", self.resid_queue
00064                 is_unreli = True
00065 
00066             else:
00067                 self.x_cur = x_pred + K_gain * y_resi # update state estimate
00068                 self.P_cur = (np.mat(np.eye(2)) - K_gain * self.H) * P_pred
00069 
00070             # record residual
00071             if len(self.resid_queue) == self.resid_q_len:
00072                 self.resid_queue.popleft()
00073             self.resid_queue.append(y_resi)
00074         else:
00075             print "NOT NEW"
00076             is_unreli = True
00077 
00078         # record is_unreli
00079         if len(self.unreli_queue) == self.unreli_q_len:
00080             self.unreli_queue.popleft()
00081         self.unreli_queue.append(is_unreli)
00082 
00083         # find the unreli level
00084         # this value [0, 1] is a record of the values which have been determined to be unreli
00085         # in the pase few seconds filtered with linear weights
00086         # a value of 0 means there are no unreliable estimates, 
00087         # 1 means there is no reliable state estimate
00088         if len(self.unreli_queue) == self.unreli_q_len:
00089             unreli_level = np.sum(self.unreli_weights * self.unreli_queue) / self.unreli_q_len
00090         else:
00091             unreli_level = 0.
00092 
00093         return self.x_cur, self.P_cur, unreli_level
00094 
00095 def homo_mat_from_2d(x, y, rot):
00096     mat2d = np.mat(trans.euler_matrix(0, 0, rot))
00097     mat2d[0,3] = x
00098     mat2d[1,3] = y
00099     return mat2d
00100 
00101 def homo_mat_to_2d(mat):
00102     rot = trans.euler_from_matrix(mat)[2]
00103     return mat[0,3], mat[1,3], rot
00104 
00105 def create_base_marker(pose, id, color):
00106     marker = Marker()
00107     marker.header.frame_id = "base_link"
00108     marker.header.stamp = rospy.Time.now()
00109     marker.ns = "ar_servo"
00110     marker.id = id
00111     marker.pose = PoseConv.to_pose_msg(pose)
00112     marker.color = ColorRGBA(*(color + (1.0,)))
00113     marker.scale.x = 0.7; marker.scale.y = 0.7; marker.scale.z = 0.2
00114     return marker
00115 
00116 class PR2ARServo(object):
00117     def __init__(self, ar_topic):
00118         self.ar_sub = rospy.Subscriber(ar_topic, ARMarker, self.ar_sub)
00119         self.mkr_pub = rospy.Publisher("visualization_marker", Marker)
00120 
00121         self.cur_ar_pose = None
00122         self.kin_arm = None
00123         self.ar_pose_updated = False
00124         self.base_pub = rospy.Publisher("/base_controller/command", Twist)
00125         self.preempt_requested = False
00126 
00127     def ar_sub(self, msg):
00128         if self.kin_arm == None:
00129             self.kin_arm = create_joint_kin(base_link="base_link", 
00130                                             end_link=msg.header.frame_id)
00131         base_B_camera = self.kin_arm.forward()
00132         camera_B_tag = PoseConv.to_homo_mat(msg.pose.pose)
00133         cur_ar_pose = base_B_camera * camera_B_tag
00134         # check to see if the tag is in front of the robot
00135         if cur_ar_pose[0,3] < 0.:
00136             #rospy.logwarn("Strange AR toolkit bug!")
00137             return
00138         self.cur_ar_pose = cur_ar_pose
00139         self.ar_pose_updated = True
00140 
00141     def request_preempt(self):
00142         self.preempt_requested = True
00143 
00144     def save_ar_goal(self):
00145         r = rospy.Rate(10)
00146         while not rospy.is_shutdown():
00147             if self.cur_ar_pose is not None:
00148                 ar_goal = homo_mat_to_2d(self.cur_ar_pose)
00149                 print ar_goal
00150             r.sleep()
00151 
00152     def test_move(self):
00153         rospy.sleep(0)
00154         base_twist = Twist()
00155         base_twist.linear.x = 0.0 #x_ctrl
00156         base_twist.linear.y = 0.0 #y_ctrl
00157         base_twist.angular.z = 0.4 #r_ctrl
00158         r = rospy.Rate(20.)
00159         while not rospy.is_shutdown():
00160             self.base_pub.publish(base_twist)
00161             r.sleep()
00162         self.base_pub.publish(Twist())
00163 
00164     def find_ar_tag(self, timeout=None):
00165         rate = 8.
00166         ar_2d_q_len = 4
00167         sigma_thresh = [0.05, 0.01, 0.08]
00168         no_mean_thresh = 0.5
00169         r = rospy.Rate(rate)
00170         ar_2d_queue = deque()
00171         new_obs_queue = deque()
00172         start_time = rospy.get_time()
00173         self.preempt_requested = False
00174         while True:
00175             if timeout is not None and rospy.get_time() - start_time > timeout:
00176                 rospy.logwarn("[pr2_viz_servo] find_ar_tag timed out, current ar_sigma: " + 
00177                               str(np.std(ar_2d_queue, 0)) +
00178                               " sigma_thresh: " +
00179                               str(sigma_thresh))
00180                 return None, 'timeout'
00181             if self.preempt_requested:
00182                 self.preempt_requested = False
00183                 return None, 'preempted'
00184             if rospy.is_shutdown():
00185                 return None, 'aborted'
00186 
00187             if self.cur_ar_pose is not None:
00188                 # make sure we have a new observation
00189                 new_obs = self.ar_pose_updated
00190                 self.ar_pose_updated = False
00191 
00192                 if new_obs:
00193                     if len(ar_2d_queue) == ar_2d_q_len:
00194                         ar_2d_queue.popleft()
00195                     ar_2d = homo_mat_to_2d(self.cur_ar_pose)
00196                     ar_2d_queue.append(ar_2d)
00197 
00198                 if len(new_obs_queue) == ar_2d_q_len:
00199                     new_obs_queue.popleft()
00200                 new_obs_queue.append(new_obs)
00201 
00202                 # see if we have a low variance tag
00203                 if len(ar_2d_queue) == ar_2d_q_len:
00204                     ar_sigma = np.std(ar_2d_queue, 0)
00205                     no_mean = np.mean(new_obs_queue, 0)
00206                     print ar_sigma, no_mean
00207                     if np.all(ar_sigma < sigma_thresh) and no_mean >= no_mean_thresh:
00208                         return np.mean(ar_2d_queue, 0), 'found_tag'
00209             r.sleep()
00210 
00211     def servo_to_tag(self, pose_goal, goal_error=[0.03, 0.03, 0.1], initial_ar_pose=None):
00212         lost_tag_thresh = 0.6 #0.4
00213 
00214         # TODO REMOVE
00215         err_pub = rospy.Publisher("servo_err", Float32MultiArray)
00216         if False:
00217             self.test_move()
00218             return "aborted"
00219         #######################
00220 
00221         goal_ar_pose = homo_mat_from_2d(*pose_goal)
00222         rate = 8.
00223         kf_x = ServoKalmanFilter(delta_t=1./rate)
00224         kf_y = ServoKalmanFilter(delta_t=1./rate)
00225         kf_r = ServoKalmanFilter(delta_t=1./rate)
00226         if initial_ar_pose is not None:
00227             ar_err = homo_mat_to_2d(homo_mat_from_2d(*initial_ar_pose) * goal_ar_pose**-1)
00228             kf_x.update(ar_err[0])
00229             kf_y.update(ar_err[1])
00230             kf_r.update(ar_err[2])
00231             print "initial_ar_pose", initial_ar_pose
00232             
00233         pid_x = PIDController(k_p=0.5, rate=rate, saturation=0.05)
00234         pid_y = PIDController(k_p=0.5, rate=rate, saturation=0.05)
00235         pid_r = PIDController(k_p=0.5, rate=rate, saturation=0.08)
00236         r = rospy.Rate(rate)
00237         self.preempt_requested = False
00238         while True:
00239             if rospy.is_shutdown():
00240                 self.base_pub.publish(Twist())
00241                 return 'aborted'
00242             if self.preempt_requested:
00243                 self.preempt_requested = False
00244                 self.base_pub.publish(Twist())
00245                 return 'preempted'
00246             goal_mkr = create_base_marker(goal_ar_pose, 0, (0., 1., 0.))
00247             self.mkr_pub.publish(goal_mkr)
00248             if self.cur_ar_pose is not None:
00249                 # make sure we have a new observation
00250                 new_obs = self.ar_pose_updated
00251                 self.ar_pose_updated = False
00252 
00253                 # find the error between the AR tag and goal pose
00254                 print "self.cur_ar_pose", self.cur_ar_pose
00255                 cur_ar_pose_2d = homo_mat_from_2d(*homo_mat_to_2d(self.cur_ar_pose))
00256                 print "cur_ar_pose_2d", cur_ar_pose_2d
00257                 ar_mkr = create_base_marker(cur_ar_pose_2d, 1, (1., 0., 0.))
00258                 self.mkr_pub.publish(ar_mkr)
00259                 ar_err = homo_mat_to_2d(cur_ar_pose_2d * goal_ar_pose**-1)
00260                 print "ar_err", ar_err
00261                 print "goal_ar_pose", goal_ar_pose
00262 
00263                 # filter this error using a Kalman filter
00264                 x_filt_err, x_filt_cov, x_unreli = kf_x.update(ar_err[0], new_obs=new_obs)
00265                 y_filt_err, y_filt_cov, y_unreli = kf_y.update(ar_err[1], new_obs=new_obs)
00266                 r_filt_err, r_filt_cov, r_unreli = kf_r.update(ar_err[2], new_obs=new_obs)
00267 
00268                 if np.any(np.array([x_unreli, y_unreli, r_unreli]) > [lost_tag_thresh]*3):
00269                     self.base_pub.publish(Twist())
00270                     return 'lost_tag'
00271 
00272                 print "Noise:", x_unreli, y_unreli, r_unreli
00273                 # TODO REMOVE
00274                 ma = Float32MultiArray()
00275                 ma.data = [x_filt_err[0,0], x_filt_err[1,0], ar_err[0], 
00276                            x_unreli, y_unreli, r_unreli]
00277                 err_pub.publish(ma)
00278 
00279                 print "xerr"
00280                 print x_filt_err
00281                 print x_filt_cov
00282                 print "Cov", x_filt_cov[0,0], y_filt_cov[0,0], r_filt_cov[0,0]
00283                 x_ctrl = pid_x.update_state(x_filt_err[0,0])
00284                 y_ctrl = pid_y.update_state(y_filt_err[0,0])
00285                 r_ctrl = pid_r.update_state(r_filt_err[0,0])
00286                 base_twist = Twist()
00287                 base_twist.linear.x = x_ctrl
00288                 base_twist.linear.y = y_ctrl
00289                 base_twist.angular.z = r_ctrl
00290                 cur_filt_err = np.array([x_filt_err[0,0], y_filt_err[0,0], r_filt_err[0,0]])
00291                 print "err", ar_err
00292                 print "Err filt", cur_filt_err 
00293                 print "Twist:", base_twist
00294                 if np.all(np.fabs(cur_filt_err) < goal_error):
00295                     self.base_pub.publish(Twist())
00296                     return 'succeeded'
00297 
00298                 self.base_pub.publish(base_twist)
00299 
00300             r.sleep()
00301 
00302 def main():
00303     rospy.init_node("pr2_viz_servo")
00304     assert(sys.argv[1] in ['r', 'l'])
00305     if sys.argv[1] == 'r':
00306         viz_servo = PR2ARServo("/r_pr2_ar_pose_marker")
00307     else:
00308         viz_servo = PR2ARServo("/l_pr2_ar_pose_marker")
00309     if False:
00310         viz_servo.save_ar_goal()
00311     elif False:
00312         viz_servo.servo_to_tag((0.55761498778404717, -0.28816809195738824, 1.5722787397126308))
00313     else:
00314         print viz_servo.find_ar_tag(5)
00315 
00316 if __name__ == "__main__":
00317     main()


hrl_pr2_ar_servo
Author(s): Kelsey Hawkins, Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab
autogenerated on Wed Nov 27 2013 11:43:43