00001
00002 import numpy as np, math
00003 import copy
00004 from threading import RLock
00005
00006 import roslib; roslib.load_manifest('hrl_pr2_lib')
00007 roslib.load_manifest('equilibrium_point_control')
00008 import rospy
00009
00010 from equilibrium_point_control.msg import MechanismKinematicsRot
00011 from equilibrium_point_control.msg import MechanismKinematicsJac
00012 from equilibrium_point_control.msg import ForceTrajectory
00013 from geometry_msgs.msg import Point32
00014 from std_msgs.msg import Empty
00015
00016 import epc
00017 import hrl_lib.util as ut
00018
00019 class Door_EPC(epc.EPC):
00020 def __init__(self, robot):
00021 epc.EPC.__init__(self, robot)
00022
00023 self.mech_kinematics_lock = RLock()
00024 self.fit_circle_lock = RLock()
00025
00026 rospy.Subscriber('mechanism_kinematics_rot',
00027 MechanismKinematicsRot,
00028 self.mechanism_kinematics_rot_cb)
00029 rospy.Subscriber('epc/stop', Empty, self.stop_cb)
00030
00031 self.force_traj_pub = rospy.Publisher('epc/force_test', ForceTrajectory)
00032 self.mech_traj_pub = rospy.Publisher('mechanism_trajectory', Point32)
00033
00034 def init_log(self):
00035 self.f_list = []
00036 self.cep_list = []
00037 self.ee_list = []
00038 self.ft = ForceTrajectory()
00039 if self.mechanism_type != '':
00040 self.ft.type = self.mechanism_type
00041 else:
00042 self.ft.type = 'rotary'
00043
00044 def log_state(self, arm):
00045
00046 f = self.robot.get_wrist_force(arm, base_frame=True)
00047 self.f_list.append(f.A1.tolist())
00048 cep, _ = self.robot.get_cep_jtt(arm, hook_tip=True)
00049 self.cep_list.append(cep.A1.tolist())
00050 ee, _ = self.robot.get_ee_jtt(arm)
00051 self.ee_list.append(ee.A1.tolist())
00052
00053 if self.started_pulling_on_handle == False:
00054 if f[0,0] > 5.:
00055 self.started_pulling_on_handle_count += 1
00056 else:
00057 self.started_pulling_on_handle_count = 0
00058 self.init_log()
00059 self.init_tangent_vector = None
00060
00061 if self.started_pulling_on_handle_count > 1:
00062 self.started_pulling_on_handle = True
00063
00064 return ''
00065
00066
00067 def stop_cb(self, cmd):
00068 self.stopping_string = 'stop_cb called.'
00069
00070 def common_stopping_conditions(self):
00071 stop = ''
00072
00073 wrist_force = self.robot.get_wrist_force(0, base_frame=True)
00074 print 'wrist_force:', wrist_force
00075 mag = np.linalg.norm(wrist_force)
00076 if mag > self.eq_force_threshold:
00077 stop = 'force exceed'
00078
00079 if mag < 1.2 and self.hooked_location_moved:
00080 if (self.prev_force_mag - mag) > 30.:
00081 stop = 'slip: force step decrease and below thresold.'
00082 else:
00083 self.slip_count += 1
00084 else:
00085 self.slip_count = 0
00086
00087 if self.slip_count == 10:
00088 stop = 'slip: force below threshold for too long.'
00089 return stop
00090
00091 def mechanism_kinematics_rot_cb(self, mk):
00092 self.fit_circle_lock.acquire()
00093 self.cx_start = mk.cx
00094 self.cy_start = mk.cy
00095 self.cz_start = mk.cz
00096 self.rad = mk.rad
00097 self.fit_circle_lock.release()
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107 def cep_gen_control_radial_force(self, arm, cep, cep_vel):
00108 self.log_state(arm)
00109 if self.started_pulling_on_handle == False:
00110 cep_vel = 0.02
00111
00112
00113 step_size = 0.1 * cep_vel
00114 stop = self.common_stopping_conditions()
00115 wrist_force = self.robot.get_wrist_force(arm, base_frame=True)
00116 mag = np.linalg.norm(wrist_force)
00117
00118 curr_pos, _ = self.robot.get_ee_jtt(arm)
00119 if len(self.ee_list)>1:
00120 start_pos = np.matrix(self.ee_list[0]).T
00121 else:
00122 start_pos = curr_pos
00123
00124
00125 if self.started_pulling_on_handle:
00126 self.mech_traj_pub.publish(Point32(curr_pos[0,0],
00127 curr_pos[1,0], curr_pos[2,0]))
00128
00129 self.fit_circle_lock.acquire()
00130 rad = self.rad
00131 cx_start, cy_start = self.cx_start, self.cy_start
00132 cz_start = self.cz_start
00133 self.fit_circle_lock.release()
00134 cx, cy = cx_start, cy_start
00135 cz = cz_start
00136 print 'cx, cy, r:', cx, cy, rad
00137
00138 radial_vec = curr_pos - np.matrix([cx,cy,cz]).T
00139 radial_vec = radial_vec/np.linalg.norm(radial_vec)
00140 if cy_start < start_pos[1,0]:
00141 tan_x,tan_y = -radial_vec[1,0],radial_vec[0,0]
00142 else:
00143 tan_x,tan_y = radial_vec[1,0],-radial_vec[0,0]
00144
00145 if tan_x > 0. and (start_pos[0,0]-curr_pos[0,0]) < 0.09:
00146 tan_x = -tan_x
00147 tan_y = -tan_y
00148
00149 if cy_start > start_pos[1,0]:
00150 radial_vec = -radial_vec
00151
00152 rv = radial_vec
00153 force_vec = np.matrix([rv[0,0], rv[1,0], 0.]).T
00154 tangential_vec = np.matrix([tan_x, tan_y, 0.]).T
00155
00156 tangential_vec_ts = tangential_vec
00157 radial_vec_ts = radial_vec
00158 force_vec_ts = force_vec
00159
00160 if arm == 'right_arm' or arm == 0:
00161 if force_vec_ts[1,0] < 0.:
00162 force_vec_ts = -force_vec_ts
00163 else:
00164 if force_vec_ts[1,0] > 0.:
00165 force_vec_ts = -force_vec_ts
00166
00167 f_vec = -1*np.array([wrist_force[0,0], wrist_force[1,0],
00168 wrist_force[2,0]])
00169 f_rad_mag = np.dot(f_vec, force_vec.A1)
00170 err = f_rad_mag-2.
00171 if err>0.:
00172 kp = -0.1
00173 else:
00174 kp = -0.2
00175 radial_motion_mag = kp * err
00176 radial_motion_vec = force_vec * radial_motion_mag
00177 eq_motion_vec = copy.copy(tangential_vec)
00178 eq_motion_vec += radial_motion_vec
00179
00180 self.prev_force_mag = mag
00181
00182 if self.init_tangent_vector == None or self.started_pulling_on_handle == False:
00183 self.init_tangent_vector = copy.copy(tangential_vec_ts)
00184 c = np.dot(tangential_vec_ts.A1, self.init_tangent_vector.A1)
00185 ang = np.arccos(c)
00186 if np.isnan(ang):
00187 ang = 0.
00188
00189 tangential_vec = tangential_vec / np.linalg.norm(tangential_vec)
00190 dist_moved = np.dot((curr_pos - start_pos).A1, tangential_vec_ts.A1)
00191 ftan = abs(np.dot(wrist_force.A1, tangential_vec.A1))
00192 self.ft.tangential_force.append(ftan)
00193 self.ft.radial_force.append(f_rad_mag)
00194
00195 if self.ft.type == 'rotary':
00196 self.ft.configuration.append(ang)
00197 else:
00198 print 'dist_moved:', dist_moved
00199 self.ft.configuration.append(dist_moved)
00200
00201 if self.started_pulling_on_handle:
00202 self.force_traj_pub.publish(self.ft)
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217 if abs(dist_moved) > 0.09 and self.hooked_location_moved == False:
00218
00219 self.hooked_location_moved = True
00220 self.eq_force_threshold = ut.bound(mag+30.,20.,80.)
00221 self.ftan_threshold = 1.2 * self.ftan_threshold + 20.
00222 if self.hooked_location_moved:
00223 if abs(tangential_vec_ts[2,0]) < 0.2 and ftan > self.ftan_threshold:
00224 stop = 'ftan threshold exceed: %f'%ftan
00225 else:
00226 self.ftan_threshold = max(self.ftan_threshold, ftan)
00227
00228 if self.hooked_location_moved and ang > math.radians(90.):
00229 print 'Angle:', math.degrees(ang)
00230 self.open_ang_exceed_count += 1
00231 if self.open_ang_exceed_count > 2:
00232 stop = 'opened mechanism through large angle: %.1f'%(math.degrees(ang))
00233 else:
00234 self.open_ang_exceed_count = 0
00235
00236 cep_t = cep + eq_motion_vec * step_size
00237 cep_t = cep + np.matrix([-1., 0., 0.]).T * step_size
00238 if cep_t[0,0] > 0.1:
00239 cep[0,0] = cep_t[0,0]
00240 cep[1,0] = cep_t[1,0]
00241 cep[2,0] = cep_t[2,0]
00242
00243 print 'CEP:', cep.A1
00244
00245 stop = stop + self.stopping_string
00246 return stop, (cep, None)
00247
00248 def pull(self, arm, force_threshold, cep_vel, mechanism_type=''):
00249 self.mechanism_type = mechanism_type
00250 self.stopping_string = ''
00251 self.eq_pt_not_moving_counter = 0
00252
00253 self.init_log()
00254
00255 self.init_tangent_vector = None
00256 self.open_ang_exceed_count = 0.
00257
00258 self.eq_force_threshold = force_threshold
00259 self.ftan_threshold = 2.
00260 self.hooked_location_moved = False
00261 self.prev_force_mag = np.linalg.norm(self.robot.get_wrist_force(arm))
00262 self.slip_count = 0
00263
00264 self.started_pulling_on_handle = False
00265 self.started_pulling_on_handle_count = 0
00266
00267 ee_pos, _ = self.robot.get_ee_jtt(arm)
00268
00269 self.cx_start = ee_pos[0,0]
00270 self.rad = 10.0
00271 self.cy_start = ee_pos[1,0]-self.rad
00272 self.cz_start = ee_pos[2,0]
00273
00274 cep, _ = self.robot.get_cep_jtt(arm)
00275 arg_list = [arm, cep, cep_vel]
00276 result, _ = self.epc_motion(self.cep_gen_control_radial_force,
00277 0.1, arm, arg_list, self.log_state,
00278
00279 control_function = self.robot.set_cep_jtt)
00280
00281 print 'EPC motion result:', result
00282 print 'Original force threshold:', force_threshold
00283 print 'Adapted force threshold:', self.eq_force_threshold
00284 print 'Adapted ftan threshold:', self.ftan_threshold
00285
00286 d = {
00287 'f_list': self.f_list, 'ee_list': self.ee_list,
00288 'cep_list': self.cep_list, 'ftan_list': self.ft.tangential_force,
00289 'config_list': self.ft.configuration, 'frad_list': self.ft.radial_force
00290 }
00291 ut.save_pickle(d,'pr2_pull_'+ut.formatted_time()+'.pkl')
00292
00293 def search_and_hook(self, arm, hook_loc, hooking_force_threshold = 5.,
00294 hit_threshold=2., hit_motions = 1,
00295 hook_direction = 'left'):
00296
00297
00298
00299
00300
00301
00302
00303
00304
00305
00306
00307 if hook_direction == 'left':
00308 offset = np.matrix([0., -0.03, 0.]).T
00309 move_dir = np.matrix([0., 1., 0.]).T
00310 elif hook_direction == 'up':
00311 offset = np.matrix([0., 0., -0.03]).T
00312 move_dir = np.matrix([0., 0., 1.]).T
00313 start_loc = hook_loc + offset
00314
00315
00316 normal_tl = np.matrix([1.0, 0., 0.]).T
00317
00318 pt1 = start_loc - normal_tl * 0.1
00319 self.robot.go_cep_jtt(arm, pt1)
00320
00321 raw_input('Hit ENTER to go')
00322
00323 vec = normal_tl * 0.2
00324 rospy.sleep(1.)
00325 for i in range(hit_motions):
00326 s = self.move_till_hit(arm, vec=vec, force_threshold=hit_threshold, speed=0.07)
00327
00328 cep_start, _ = self.robot.get_cep_jtt(arm)
00329 cep = copy.copy(cep_start)
00330 arg_list = [arm, move_dir, hooking_force_threshold, cep, cep_start]
00331 s = self.epc_motion(self.cep_gen_surface_follow, 0.1, arm,
00332 arg_list, control_function = self.robot.set_cep_jtt)
00333 return s
00334
00335
00336 if __name__ == '__main__':
00337 import pr2_arms as pa
00338 rospy.init_node('epc_pr2', anonymous = True)
00339 rospy.logout('epc_pr2: ready')
00340
00341 pr2_arms = pa.PR2Arms()
00342 door_epc = Door_EPC(pr2_arms)
00343
00344 r_arm, l_arm = 0, 1
00345 arm = r_arm
00346
00347 raw_input('Hit ENTER to close')
00348 pr2_arms.close_gripper(arm)
00349 raw_input('Hit ENTER to start Door Opening')
00350
00351
00352
00353
00354 p1 = np.matrix([0.8, -0.1, -0.04]).T
00355 door_epc.search_and_hook(arm, p1, hook_direction='left')
00356 door_epc.pull(arm, force_threshold=40., cep_vel=0.05)
00357
00358
00359
00360
00361
00362
00363