示例#1
0
def segment_point_distance(a, b, x):
    """Returns (distance, parameter) pair between segment (a,b) and point x"""
    d = vectorops.sub(b, a)
    u = vectorops.dot(vectorops.sub(x, a), d) / vectorops.dot(d, d)
    u = min(1.0, max(u, 0.0))
    d = vectorops.distance(x, vectorops.interpolate(a, b, u))
    return (d, u)
示例#2
0
def segment_triangle_intersection(seg, tri, umin=0, umax=1):
    """Given a 3D segment (p,q) and a triangle (a,b,c), returns the point of
	intersection if the region of the segment in interval [umin,umax] intersects the
	triangle. Otherwise returns None"""
    p, q = seg
    a, b, c = tri
    d = vectorops.sub(b, a)
    e = vectorops.sub(c, a)
    n = vectorops.cross(d, e)
    if vectorops.norm(n) < 1e-7:  #degenerate
        return None
    n = vectorops.unit(n)
    ofs = vectorops.dot(n, a)
    #Solve for n^T(p + u(q-p)) = ofs
    denom = vectorops.dot(n, vectorops.sub(q, p))
    numer = ofs - vectorops.dot(n, p)
    if abs(denom) < 1e-7:  #near parallel
        return None
    u = numer / denom
    if u < umin or u > umax:
        return None
    #now check whether point of intersection lies in triangle
    x = vectorops.madd(p, vectorops.sub(q, p), u)
    xloc = vectorops.sub(x, a)

    #solve for coordinates [r,s,t] such that xloc = r*n + s*d + t*e
    try:
        rst = np.dot(np.linalg.inv(np.array([n, d, e]).T), xloc)
    except np.linalg.linalg.LinAlgError:
        return None
    r, s, t = rst
    assert abs(r) < 1e-4
    if s >= 0 and t >= 0 and s + t <= 1:
        return x
    return None
    def apply_tendon_forces(self,i,link1,link2,rest_length):
        tendon_c2 = 30000.0
        tendon_c1 = 10000.0
        b0 = self.sim.body(self.model.robot.link(self.model.proximal_links[0]-3))
        b1 = self.sim.body(self.model.robot.link(link1))
        b2 = self.sim.body(self.model.robot.link(link2))
        p0w = se3.apply(b1.getTransform(),self.tendon0_local)
        p1w = se3.apply(b1.getTransform(),self.tendon1_local)
        p2w = se3.apply(b2.getTransform(),self.tendon2_local)

        d = vectorops.distance(p1w,p2w)
        if d > rest_length:
            #apply tendon force
            direction = vectorops.unit(vectorops.sub(p2w,p1w))
            f = tendon_c2*(d - rest_length)**2+tendon_c1*(d - rest_length)
            #print d,rest_length
            #print "Force magnitude",self.model.robot.link(link1).getName(),":",f
            f = min(f,100)
            #tendon routing force
            straight = vectorops.unit(vectorops.sub(p2w,p0w))
            pulley_direction = vectorops.unit(vectorops.sub(p1w,p0w))
            pulley_axis = so3.apply(b1.getTransform()[0],(0,1,0))
            tangential_axis = vectorops.cross(pulley_axis,pulley_direction)
            cosangle = vectorops.dot(straight,tangential_axis)
            #print "Cosine angle",self.model.robot.link(link1).getName(),cosangle
            base_direction = so3.apply(b0.getTransform()[0],[0,0,-1])
            b0.applyForceAtLocalPoint(vectorops.mul(base_direction,-f),vectorops.madd(p0w,base_direction,0.04))
            b1.applyForceAtLocalPoint(vectorops.mul(tangential_axis,cosangle*f),self.tendon1_local)
            b1.applyForceAtLocalPoint(vectorops.mul(tangential_axis,-cosangle*f),self.tendon0_local)
            b2.applyForceAtLocalPoint(vectorops.mul(direction,-f),self.tendon2_local)
            self.forces[i][1] = vectorops.mul(tangential_axis,cosangle*f)
            self.forces[i][2] = vectorops.mul(direction,f)
        else:
            self.forces[i] = [None,None,None]
        return
示例#4
0
def mmult(A, b):
    """Matrix-vector multiplication with raw Python objects"""
    v = []
    for ai in A:
        assert (len(ai) == len(b))
        v.append(vectorops.dot(ai, b))
    return v
示例#5
0
def draw_hull(hull,scale=0.01):
    """Draws a ConvexHull with 3D texture coordinates"""
    if len(hull.simplices)==0:
        print "Hull with no simplices?"
        return
    centroid = sum([hull.points[v] for v in hull.vertices],[0.0]*3) / len(hull.vertices) * scale
    vmin = [min([hull.points[v][i] for v in hull.vertices])*scale for i in range(3)]
    vmax = [max([hull.points[v][i] for v in hull.vertices])*scale for i in range(3)]
    uvwscale = [1.0/(b-a) if b != a else 1.0 for (a,b) in zip(vmin,vmax)]

    for simplex in hull.simplices:
        ia,ib,ic = simplex
        a = vectorops.mul(hull.points[ia].tolist(),scale)
        b = vectorops.mul(hull.points[ib].tolist(),scale)
        c = vectorops.mul(hull.points[ic].tolist(),scale)
        n = vectorops.cross(vectorops.sub(b,a),vectorops.sub(c,a))
        if vectorops.dot(n,vectorops.sub(centroid,a)) > 0:
            b,c = c,b
            n = vectorops.mul(n,-1)
        try:
            n = vectorops.mul(n,1.0/vectorops.norm(n))
            glNormal3f(*n)
        except ZeroDivisionError:
            pass
        glBegin(GL_TRIANGLES)
        glTexCoord3f(uvwscale[0]*(a[0]-vmin[0]),uvwscale[1]*(a[1]-vmin[1]),uvwscale[2]*(a[2]-vmin[2]))
        glVertex3f(*a)
        glTexCoord3f(uvwscale[0]*(b[0]-vmin[0]),uvwscale[1]*(b[1]-vmin[1]),uvwscale[2]*(b[2]-vmin[2]))
        glVertex3f(*b)
        glTexCoord3f(uvwscale[0]*(c[0]-vmin[0]),uvwscale[1]*(c[1]-vmin[1]),uvwscale[2]*(c[2]-vmin[2]))
        glVertex3f(*c)
        glEnd()
示例#6
0
def axis_rotation_magnitude(R, a):
    """Given a rotation matrix R and a unit axis a, determines how far R rotates
    about a. Specifically, if R = from_axis_angle((a,v)) this should return v (modulo pi).
    """
    cterm = so3.trace(R) - vectorops.dot(a, so3.apply(R, a))
    mR = so3.matrix(R)
    sterm = -(a[0] * (mR[1][2] - mR[2][1]) + a[1] *
              (mR[2][0] - mR[0][2]) + a[2] * (mR[0][1] - mR[1][0]))
    return math.atan2(sterm, cterm)
示例#7
0
 def config_to_opening(self,qfinger):
     """Estimates far qfinger is from closed_config to open_config.
     Only meaningful if qfinger is close to being along the straight
     C-space line between the two.
     """
     if self.closed_config is None or self.open_config is None:
         raise ValueError("Can't estimate opening width to")
     assert len(qfinger) == len(self.closed_config)
     b = vectorops.sub(qfinger,self.closed_config)
     a = vectorops.sub(self.open_config,self.closed_config)
     return min(1,max(0,vectorops.dot(a,b)/vectorops.normSquared(a)))
示例#8
0
    def init(self, scene, object, hints):
        """Needs object to contain a structured PointCloud."""
        if not isinstance(object, (RigidObjectModel, Geometry3D, PointCloud)):
            print(
                "Need to pass an object as a RigidObjectModel, Geometry3D, or PointCloud"
            )
            return False
        if isinstance(object, RigidObjectModel):
            return self.init(scene, object.geometry(), hints)
        pc = None
        xform = None
        if isinstance(object, Geometry3D):
            pc = object.getPointCloud()
            xform = object.getCurrentTransform()
        else:
            pc = object
            xform = se3.identity()
        self.pc = pc
        self.pc_xform = xform

        #now look through PC and find flat parts
        #do a spatial hash
        from collections import defaultdict
        estimation_knn = 6
        pts = numpy_convert.to_numpy(pc)
        N = pts.shape[0]
        positions = pts[:, :3]
        normals = np.zeros((N, 3))
        indices = (positions * (1.0 / self._gripper.opening_span)).astype(int)
        pt_hash = defaultdict(list)
        for i, (ind, p) in enumerate(zip(indices, positions)):
            pt_hash[ind].append((i, p))
        options = []
        for (ind, iplist) in pt_hash.items():
            if len(iplist) < estimation_knn:
                pass
            else:
                pindices = [ip[0] for ip in iplist]
                pts = [ip[1] for ip in iplist]
                c, n = fit_plane_centroid(pts)
                if n[2] < 0:
                    n = vectorops.mul(n, -1)
                verticality = self.vertical_penalty(math.acos(n[2]))
                var = sum(
                    vectorops.dot(vectorops.sub(p, c), n)**2 for p in pts)
                roughness = self.roughness_penalty(var)
                options.append((cn, n, verticality + roughness))
        if len(options) == 0:
            return False
        self.options = options.sorted(key=lambda x: -x[2])
        self.index = 0
        return True
示例#9
0
    def click_world(self,x,y):
        """Helper: returns a list of world objects sorted in order of
        increasing distance."""
        #get the viewport ray
        (s,d) = self.click_ray(x,y)

        #run the collision tests
        collided = []
        for g in self.collider.geomList:
            (hit,pt) = g[1].rayCast(s,d)
            if hit:
                dist = vectorops.dot(vectorops.sub(pt,s),d)
                collided.append((dist,g[0]))
        return [g[1] for g in sorted(collided)]
示例#10
0
def score_function(grasping_problem, point, linkgeom_idx, CoM,
                   balance_residual, x, y, z):
    """
    Calculate the goodness of a point for satisfying the constraints in a grasping planning problem. 
    """

    # Goodness for force balance -- sort of like a cosine similarity
    a1 = -vectorops.dot(balance_residual[:3],
                        normal(grasping_problem.complementarity.obj, point))

    # Distance to the object
    dist = (
        grasping_problem.complementarity.robot.geometry[linkgeom_idx].distance(
            list(point)))[0]
    a2 = math.exp(-dist)

    return a1 + a2
示例#11
0
    def apply_tendon_forces(self, i, link1, link2, rest_length):
        tendon_c2 = 30000.0
        tendon_c1 = 10000.0
        b0 = self.sim.body(
            self.model.robot.link(self.model.proximal_links[0] - 3))
        b1 = self.sim.body(self.model.robot.link(link1))
        b2 = self.sim.body(self.model.robot.link(link2))
        p0w = se3.apply(b1.getTransform(), self.tendon0_local)
        p1w = se3.apply(b1.getTransform(), self.tendon1_local)
        p2w = se3.apply(b2.getTransform(), self.tendon2_local)

        d = vectorops.distance(p1w, p2w)
        if d > rest_length:
            #apply tendon force
            direction = vectorops.unit(vectorops.sub(p2w, p1w))
            f = tendon_c2 * (d - rest_length)**2 + tendon_c1 * (d -
                                                                rest_length)
            #print d,rest_length
            #print "Force magnitude",self.model.robot.link(link1).getName(),":",f
            f = min(f, 100)
            #tendon routing force
            straight = vectorops.unit(vectorops.sub(p2w, p0w))
            pulley_direction = vectorops.unit(vectorops.sub(p1w, p0w))
            pulley_axis = so3.apply(b1.getTransform()[0], (0, 1, 0))
            tangential_axis = vectorops.cross(pulley_axis, pulley_direction)
            cosangle = vectorops.dot(straight, tangential_axis)
            #print "Cosine angle",self.model.robot.link(link1).getName(),cosangle
            base_direction = so3.apply(b0.getTransform()[0], [0, 0, -1])
            b0.applyForceAtLocalPoint(
                vectorops.mul(base_direction, -f),
                vectorops.madd(p0w, base_direction, 0.04))
            b1.applyForceAtLocalPoint(
                vectorops.mul(tangential_axis, cosangle * f),
                self.tendon1_local)
            b1.applyForceAtLocalPoint(
                vectorops.mul(tangential_axis, -cosangle * f),
                self.tendon0_local)
            b2.applyForceAtLocalPoint(vectorops.mul(direction, -f),
                                      self.tendon2_local)
            self.forces[i][1] = vectorops.mul(tangential_axis, cosangle * f)
            self.forces[i][2] = vectorops.mul(direction, f)
        else:
            self.forces[i] = [None, None, None]
        return
示例#12
0
def run_poking_point_probe(config,tableHeight,probeLength,forceLimit,dt,moveStep,shortServoTime,longServoTime,
								IKErrorTolerence,maxDev,EEZLimit,probe_transform,point_probe_to_local,world,res,
								robot,link,CONTROLLER,collider,intermediateConfig):
	"""
	this is the main function of poking object. - point probe
	"""
	# Read In the pcd 
	points, normals = load_pcd(config.exp_path+'exp_'+str(config.exp_number)+'/probePcd.txt')
	
	# control interface
	if CONTROLLER == 'physical':
		robotControlApi = UR5WithGripperController(host=config.robot_host,gripper=False)
		robotControlApi.start()
		time.sleep(2)
		print '---------------------robot started -----------------------------'
		constantVServo(robotControlApi,4,intermediateConfig,dt)#controller format

	# in simulation ,set
	robot.setConfig(controller_2_klampt(robot,intermediateConfig))
	print '---------------------at home configuration -----------------------------'

	if CONTROLLER == 'debugging':
		differences=[]
		print('[*]Debug: Poking process start!')

		for i in range(len(points)):
			print('point %d, pos: %s, normals: %s'%(i,points[i],normals[i]))
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0)) #get unit vector in the direction '- normals'

			## perform IK
			local_NY_UnitV=vectorops.unit(vectorops.cross([0,1,0],approachVector))			
			pt1=goalPosition
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength)) # use 1m in normals direction.			
			pt3=vectorops.add(pt1,local_NY_UnitV)

			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],maxDev,
											IKErrorTolerence,EEZLimit,collider,use_collision_detect=True)
			differences.append(difference)
			print('difference: %f'%difference)

			### now start colecting data..
			travel = 0.0
			stepVector = vectorops.mul(approachVector,moveStep)
			
			while travel<0.0001: #just try 0.1mm?
				pt1=vectorops.add(pt1,stepVector)
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
				pt3=vectorops.add(pt1,local_NY_UnitV)
				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],maxDev,
												IKErrorTolerence,EEZLimit,collider,use_const=False)
				travel = travel + moveStep
				
			### move the probe away, note: a bit different to physical mode
			pt1=vectorops.add(points[i],vectorops.mul(approachVector,-0.05))  ## move the probe 5 cm from the object surface
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
			pt3=vectorops.add(pt1,local_NY_UnitV)
			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],maxDev,
											IKErrorTolerence,EEZLimit,collider)

			### move back to intermediate config
			robot.setConfig(controller_2_klampt(robot,intermediateConfig))
		
		print('[*]Debug: Poking process done, with max difference:%f'%max(differences))
		
		vis.show()
		while vis.shown():
			time.sleep(1.0)

	elif CONTROLLER == 'physical':
		input('There are %d poking point, go?'%len(points))
		point_list = range(112,116) # !delete 85, 90
		#point_list = random.sample(range(97),97)

		#point_list = [40,37,67,68]
		for i in point_list:	
			print('point %d, pos: %s, normals: %s'%(i,points[i],normals[i]))
			
			travel = -0.01
			#init record file
			forceData=open(config.exp_path+'exp_'+str(config.exp_number)+'/point/force_'+str(i)+'.txt','w')

			robotCurrentConfig=robotControlApi.getConfig()
			robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
			#calculate start position
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0))
			#### Make sure no contact, backup 0.01m
			local_NY_UnitV=vectorops.unit(vectorops.cross([0,1,0],approachVector))

			pt1=vectorops.add(goalPosition,vectorops.mul(approachVector,travel))
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))			
			pt3=vectorops.add(pt1,local_NY_UnitV)

			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime-1,dt) #TODO:

			time.sleep(0.2)

			# Zero the sensor before straight line push, Note that the force is recorded in the global frame..
			counter = 0.0
			totalF = [0,0,0]
			startTime=time.time()
			while (time.time()-startTime) < 1: # use 1s to cal the Force
				totalF = vectorops.add(totalF,robotControlApi.getWrench()[0:3])
				counter = counter + 1.0
				time.sleep(dt)
			forceBias = vectorops.mul(totalF,1.0/float(counter)) # when probe no touch the obj, F_avr = sum(F)/n

			### now start collecting data..
			wrench = robotControlApi.getWrench()
			Force = vectorops.sub(wrench[0:3],forceBias)
			Force_normal = math.fabs(vectorops.dot(Force,approachVector)) #|F||n|cos(theta) = F dot n, set it >= 0 
						
			forceHistory = [Force]			
			force_normalHistory = [Force_normal]
			displacementHistory = [travel]
			stepVector = vectorops.mul(approachVector,moveStep)

			while Force_normal < forceLimit:
				robotCurrentConfig=robotControlApi.getConfig()
				robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
				pt1=vectorops.add(pt1,stepVector)
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
				pt3=vectorops.add(pt1,local_NY_UnitV)
				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
												maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime,dt,use_const=False)
				time.sleep(dt)

				Force = vectorops.sub(robotControlApi.getWrench()[0:3],forceBias)
				Force_normal = math.fabs(vectorops.dot(Force,approachVector))
				travel = travel + moveStep

				forceHistory.append([Force[0],Force[1],Force[2]])				
				force_normalHistory.append(Force_normal)
				displacementHistory.append(travel)
			
			#record all the data in 2 files, one N*2 containts all the force data collected at various locations, another
			#file specifies the number of datapoints at each detected point
			for (f,fn,d) in zip(forceHistory,force_normalHistory,displacementHistory):
				forceData.write(str(f[0])+' '+str(f[1])+' '+str(f[2])+' '+str(fn)+' '+str(d)+'\n')
			forceData.close()

			### move the probe away
			robotCurrentConfig=robotControlApi.getConfig()
			robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
			pt1=vectorops.add(points[i],vectorops.mul(approachVector,-0.10))  ## move the probe 8 cm from the object surface
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
			pt3=vectorops.add(pt1,local_NY_UnitV)
			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,shortServoTime,dt)
			
			#constantVServo(robotControlApi,longServoTime,intermediateConfig,dt)

			print'----------------------- pt '+str(i)+' completed -------------------------------'
		
		#### move back to intermediate config
		constantVServo(robotControlApi,shortServoTime,intermediateConfig,dt)	
		robotControlApi.stop()
示例#13
0
 def moveForceSpring(self, x, y):
     self.sim.updateWorld()
     (s, d) = self.view.click_ray(x, y)
     u = vectorops.dot(vectorops.sub(self.forceAnchorPoint, s), d)
     self.forceAnchorPoint = vectorops.madd(s, d, u)
def predict_line(lineStarts,lineEnds,lineNormals,lineTorqueAxes,pcd,param,discretization,num_iter,queryDList,vis,world):
    vision_task_1 = False#True means we are doing the collision detection.
    o3d = False
    #create a pcd in open3D
    equilibriumPcd = open3d.geometry.PointCloud()
    xyz = []
    rgb = []
    normals = []
    for ele in pcd:
        xyz.append(ele[0:3])
        rgb.append(ele[3:6])
        normals.append(ele[6:9])
    equilibriumPcd.points = open3d.utility.Vector3dVector(np.asarray(xyz,dtype=np.float32))
    equilibriumPcd.colors = open3d.utility.Vector3dVector(np.asarray(rgb,dtype=np.float32))
    equilibriumPcd.normals = open3d.utility.Vector3dVector(np.asarray(normals,dtype=np.float32))
    # equilibriumPcd,ind=statistical_outlier_removal(equilibriumPcd,nb_neighbors=20,std_ratio=0.75) 
    if o3d:
        vis3 = open3d.visualization.Visualizer()
        vis3.create_window()
        open3dPcd = open3d.geometry.PointCloud()
        vis3.add_geometry(open3dPcd)

    probe = world.rigidObject(0)
    klampt_pcd_object = world.rigidObject(1) #this is a rigid object
    klampt_pcd = klampt_pcd_object.geometry().getPointCloud() #this is now a PointCloud()
    N_pts = klampt_pcd.numPoints()
    dt = 0.1
   

    for pointNumber in num_iter:

        ####Preprocess the pcd ####
        lineStart0 = lineStarts[pointNumber]
        lineEnd0 =lineEnds[pointNumber]
        lineTorqueAxis = lineTorqueAxes[pointNumber]
        N = 1 + round(vo.norm(vo.sub(lineStart0,lineEnd0))/discretization)
        s = np.linspace(0,1,N)
        lineNormal = lineNormals[pointNumber]
        localXinW = vo.sub(lineEnd0,lineStart0)/np.linalg.norm(vo.sub(lineEnd0,lineStart0))
        localYinW = (lineTorqueAxis)/np.linalg.norm(lineTorqueAxis)
        lineStartinLocal = [0,0]
        lineEndinLocal = [np.dot(vo.sub(lineEnd0,lineStart0),localXinW),
                        np.dot(vo.sub(lineEnd0,lineStart0),localYinW)]
        #################first project the pcd to the plane of the line##############
        #The start point is the origin of the plane...
        projectedPcd = [] #Each point is R^10 
        projectedPcdLocal = [] #localXY coordinate
        #the projected Pcd is in local frame....
        for i in range(len(pcd)):
            p = pcd[i][0:3]
            projectedPt = vo.sub(p,vo.mul(lineNormal,vo.dot(vo.sub(p,lineStart0),lineNormal))) ##world origin
            projectedPt2D = vo.sub(projectedPt,lineStart0)#world origin
            projectedPt2DinLocal = [vo.dot(projectedPt2D,localXinW),vo.dot(projectedPt2D,localYinW)]
            #%make sure point is in the "box" defined by the line
            if ((projectedPt2DinLocal[0]<0.051) and (projectedPt2DinLocal[0] > -0.001)
                and (projectedPt2DinLocal[1]<0.001) and (projectedPt2DinLocal[1]>-0.001)):
                projectedPcdLocal.append(projectedPt2DinLocal)
                projectedPcd.append(pcd[i])
        #Create a KDTree for searching
        projectedPcdTree = spatial.KDTree(projectedPcdLocal)
        ###############Find the corresponding point on the surface to the line############
        surfacePtsAll = []# %These are the surface pts that will be displaced.
        #%part of the probe not in contact with the object...
        #average 3 neighbors
        NofN = 3
        #rigidPointsFinal = []   ##we have a potential bug here for not using rigidPointsFinal....      
        for i in range(int(N)):
            tmp =vo.mul(vo.sub(lineEnd0,lineStart0),s[i])#%the point on the line, projected 
            linePt = [vo.dot(tmp,localXinW),vo.dot(tmp,localYinW)]
            d,Idx = projectedPcdTree.query(linePt[0:2],k=NofN)
            #We might end up having duplicated pts...
            #We should make sure that the discretization is not too fine..
            #or should average a few neighbors
            if d[0] < 0.002:
                surfacePt = [0]*10
                for j in range(NofN):
                    surfacePt = vo.add(surfacePt,projectedPcd[Idx[j]][0:10])
                surfacePt = vo.div(surfacePt,NofN)
                surfacePtsAll.append(surfacePt) #position in the global frame..
                #rigidPointsFinal.append(linePts)

        N = len(surfacePtsAll)

        ##### Preprocesss done
        if not o3d:
            vis.show()
            time.sleep(15.0)
        ############# Go through a list of displacements
        totalFinNList = []
        #for queryD = -0.003:0.001:0.014
        for queryD in queryDList:
            lineStart = vo.sub(lineStart0,vo.mul(lineNormal,queryD))
            lineEnd = vo.sub(lineEnd0,vo.mul(lineNormal,queryD))
            lineCenter = vo.div(vo.add(lineStart,lineEnd),2)
            torqueCenter = vo.add(lineCenter,vo.mul(lineNormal,0.09))


            if vision_task_1:

                vis.lock()
                print(queryD)
                x_axis = vo.mul(vo.unit(vo.sub(lineEnd,lineStart)),-1.0)
                y_axis = [lineTorqueAxis[0],lineTorqueAxis[1],lineTorqueAxis[2]]
                z_axis = vo.cross(x_axis,y_axis)
                z_axis = [z_axis[0],z_axis[1],z_axis[2]]
                R = x_axis+y_axis+z_axis
                t = vo.add(lineCenter,vo.mul(lineNormal,0.002))
                
                print(R,t)
                probe.setTransform(R,t)
                vis.unlock()
                time.sleep(dt)
            else:
                if not o3d:
                    vis.lock()
                print(queryD)
                x_axis = vo.mul(vo.unit(vo.sub(lineEnd,lineStart)),-1.0)
                y_axis = [lineTorqueAxis[0],lineTorqueAxis[1],lineTorqueAxis[2]]
                z_axis = vo.cross(x_axis,y_axis)
                z_axis = [z_axis[0],z_axis[1],z_axis[2]]
                R = x_axis+y_axis+z_axis
                t = vo.add(lineCenter,vo.mul(lineNormal,0.003))
                probe.setTransform(R,t)
                

                ####calculate the nominal displacements
                surfacePts = [] #These are the surface pts that will be displaced...
                rigidPtsInContact = []
                nominalD = [] #Column Vector..
                for i in range(int(N)): ##we have a potential bug here for keep interating trhough N, since about, if d[0] < 0.002, the points is not added...
                    #weird no bug occured...
                    linePt = vo.add(vo.mul(vo.sub(lineEnd,lineStart),s[i]),lineStart)              
                    surfacePt = surfacePtsAll[i][0:3]
                    normal = surfacePtsAll[i][6:9]
                    nominalDisp = -vo.dot(vo.sub(linePt,surfacePt),normal)
                    if nominalDisp > 0:
                        surfacePts.append(surfacePtsAll[i][0:10])#position in the global frame..
                        rigidPtsInContact.append(linePt)
                        nominalD.append(nominalDisp)
                originalNominalD = deepcopy(nominalD)
                NofSurfacePts = len(surfacePts)
                if NofSurfacePts > 0:
                    negativeDisp = True
                    while negativeDisp:
                        NofSurfacePts = len(surfacePts)
                        K = np.zeros((NofSurfacePts,NofSurfacePts))
                        for i in range(NofSurfacePts):
                            for j in range(NofSurfacePts):
                                K[i][j] = invKernel(surfacePts[i][0:3],surfacePts[j][0:3],param)
                        #print K
                        #startTime = time.time()
                        actualD =  np.dot(np.linalg.inv(K),nominalD)
                        #print('Time spent inverting matrix',time.time()- startTime)
                        #print nominalD,actualD
                        negativeIndex = actualD < 0
                        if np.sum(negativeIndex) > 0:
                            actualD = actualD.tolist()
                            surfacePts = [surfacePts[i] for i in range(len(surfacePts)) if actualD[i]>=0]
                            nominalD = [nominalD[i] for i in range(len(nominalD)) if actualD[i]>=0]
                            rigidPtsInContact = [rigidPtsInContact[i] for i in range(len(rigidPtsInContact)) if actualD[i]>=0]
                        else:
                            negativeDisp = False
                    
                    
                    #hsv's  hue: 0.25 = 0.0002 displacement 1 == 10 displacement
                    #generate the entire displacement field
                    #surfacePts are the equlibrium pts that provide 
                    entireDisplacedPcd = []
                    colorThreshold = 0.0005
                    colorUpperBound = 0.012
                    forceColorUpperBound = 0.004
                    colorRange = colorUpperBound - colorThreshold
                    greyColor = 0.38
                    
                    xyz = []
                    rgb = []
                    xyzForce = []
                    rgbForce = []
                    maxDisp = 0
                    for pt,ptNormal in zip(equilibriumPcd.points,equilibriumPcd.normals):
                        shapeVector = []
                        for pt2 in surfacePts:
                            shapeVector.append(invKernel(pt[0:3],pt2[0:3],param))
                        nominalDisplacement = vo.dot(shapeVector,actualD)
                        if nominalDisplacement > maxDisp:
                            maxDisp = nominalDisplacement

                        color = colorsys.hsv_to_rgb(nominalDisplacement/colorRange*0.75+0.25,1,0.75)
                        color = [color[0],color[1],color[2]]
                        displacedDeformablePoint = vo.sub(pt[0:3],vo.mul(ptNormal,nominalDisplacement))
                        xyz.append(displacedDeformablePoint)
                        rgb.append(color)
                        

                    counter = 0 
                    for (p,c) in zip(xyz,equilibriumPcd.colors):#rgb):
                        klampt_pcd.setProperty(counter,'r',c[0])
                        klampt_pcd.setProperty(counter,'g',c[1])
                        klampt_pcd.setProperty(counter,'b',c[2])
                        klampt_pcd.setPoint(counter,p)
                        counter = counter + 1
                    klampt_pcd_object.geometry().setPointCloud(klampt_pcd)
                    if o3d:
                        open3dPcd.points = open3d.utility.Vector3dVector(np.asarray(xyz,dtype=np.float32))
                        open3dPcd.colors = open3d.utility.Vector3dVector(np.asarray(rgb,dtype=np.float32))
                        open3dPcd.estimate_normals(search_param = open3d.geometry.KDTreeSearchParamHybrid(radius = 0.1, max_nn = 30))
                        ###open3dPcd,ind=statistical_outlier_removal(open3dPcd,nb_neighbors=10,std_ratio=2) 
                        #open3d.visualization.draw_geometries([open3dPcd])#_box_bottom])
                        vis3.add_geometry(open3dPcd)
                        vis3.poll_events()
                        vis3.update_renderer()
                    if not o3d:
                        vis.unlock()
                    time.sleep(dt)
                else:
                    pass

        
        while vis.shown():
            time.sleep(0.1)
    return
示例#15
0
    def drive(self, qcur, angVel, vel, dt):
        """Drives the robot by an incremental time step to reach the desired
        Cartesian (angular/linear) velocities of the links previously specified
        in start().

        Args:
            qcur (list of floats): The robot's current configuration.
            angVel (3-vector or list of 3-vectors): the angular velocity of
                each driven link.  Set angVel to None to turn off orientation
                control of every constraint. angVel[i] to None to turn off
                orientation control of constraint i.
            vel (3-vector or list of 3-vectors): the linear velocity of each
                driven link.  Set vel to None to turn off position control of
                every constraint.  Set vel[i] to None to turn off position 
                control of constraint i.
            dt (float): the time step.

        Returns:
            tuple: A pair ``(progress,qnext)``. ``progress`` gives a value
            in the range [0,1] indicating indicating how far along the nominal
            drive amount the solver was able to achieve.  If the result is < 0,
            this indicates that the solver failed to make further progress.

            ``qnext`` is the resulting configuration that should be sent to the
            robot's controller.

        For longer moves, you should pass qnext back to this function as qcur.
        """
        if angVel is None:
            #turn off orientation control
            if vel is None:
                #nothing specified
                return (1.0, qcur)
            angVel = [None] * len(self.links)
        else:
            assert len(angVel) > 0
            if not hasattr(angVel[0], '__iter__'):
                angVel = [angVel]
        if vel is None:
            #turn off position control
            vel = [None] * len(self.links)
        else:
            assert len(vel) > 0
            if not hasattr(vel[0], '__iter__'):
                vel = [vel]
        if len(qcur) != self.robot.numLinks():
            raise ValueError(
                "Invalid size of current configuration, %d != %d" %
                (len(qcur), self.robot.numLinks()))
        if len(angVel) != len(self.links):
            raise ValueError(
                "Invalid # of angular velocities specified, %d != %d" %
                (len(angVel), len(self.links)))
        if len(vel) != len(self.links):
            raise ValueError(
                "Invalid # of translational velocities specified, %d != %d" %
                (len(vel), len(self.links)))
        anyNonzero = False
        zeroVec = [0, 0, 0]
        for (w, v) in zip(angVel, vel):
            if w is not None and list(w) != zeroVec:
                anyNonzero = True
                break
            if v is not None and list(v) != zeroVec:
                anyNonzero = True
                break
        if not anyNonzero:
            return (1.0, qcur)

        qout = [v for v in qcur]

        #update drive transforms
        self.robot.setConfig(qcur)
        robotLinks = [self.robot.link(l) for l in self.links]

        #limit the joint movement by joint limits and velocity
        tempqmin, tempqmax = self.robot.getJointLimits()
        if self.qmin is not None:
            tempqmin = self.qmin
        if self.qmax is not None:
            tempqmax = self.qmax
        vmax = self.robot.getVelocityLimits()
        vmin = vectorops.mul(vmax, -1)
        if self.vmin is not None:
            vmin = self.vmin
        if self.vmax is not None:
            vmax = self.vmax
        for i in range(self.robot.numLinks()):
            tempqmin[i] = max(tempqmin[i], qcur[i] + dt * vmin[i])
            tempqmax[i] = min(tempqmax[i], qcur[i] + dt * vmax[i])

        #Setup the IK solver parameters
        self.solver.setJointLimits(tempqmin, tempqmax)
        tempGoals = [ik.IKObjective(g) for g in self.ikGoals]
        for i in range(len(self.links)):
            if math.isfinite(self.positionTolerance) and math.isfinite(
                    self.rotationTolerance):
                tempGoals[i].rotationScale = self.positionTolerance / (
                    self.positionTolerance + self.rotationTolerance)
                tempGoals[i].positionScale = self.rotationTolerance / (
                    self.positionTolerance + self.rotationTolerance)
            elif not math.isfinite(
                    self.positionTolerance) and not math.isfinite(
                        self.rotationTolerance):
                pass
            else:
                tempGoals[i].rotationScale = min(
                    self.positionTolerance,
                    self.rotationTolerance) / self.rotationTolerance
                tempGoals[i].positionScale = min(
                    self.positionTolerance,
                    self.rotationTolerance) / self.positionTolerance
        tolerance = min(
            1e-6,
            min(self.positionTolerance, self.rotationTolerance) /
            (math.sqrt(3.0) * len(self.links)))
        self.solver.setTolerance(tolerance)

        #want to solve max_t s.t. there exists q satisfying T_i(q) = TPath_i(t)
        #where TPath_i(t) = Advance(Tdrive_i,Screw_i*t)
        if self.driveSpeedAdjustment == 0:
            self.driveSpeedAdjustment = 0.1
        anyFailures = False
        while self.driveSpeedAdjustment > 0:
            #advance the desired cartesian goals
            #set up IK parameters: active dofs, IKGoal
            amount = dt * self.driveSpeedAdjustment
            desiredTransforms = [[None, None] for i in range(len(self.links))]
            for i in range(len(self.links)):
                if vel[i] is not None:
                    desiredTransforms[i][1] = vectorops.madd(
                        self.driveTransforms[i][1], vel[i], amount)
                    tempGoals[i].setFixedPosConstraint(
                        self.endEffectorOffsets[i], desiredTransforms[i][1])
                else:
                    tempGoals[i].setFreePosition()
                if angVel[i] is not None:
                    increment = so3.from_moment(
                        vectorops.mul(angVel[i], amount))
                    desiredTransforms[i][0] = so3.mul(
                        increment, self.driveTransforms[i][0])
                    tempGoals[i].setFixedRotConstraint(desiredTransforms[i][0])
                else:
                    tempGoals[i].setFreeRotConstraint()
                self.solver.set(i, tempGoals[i])

            err0 = self.solver.getResidual()
            quality0 = vectorops.norm(err0)

            res = self.solver.solve()
            q = self.robot.getConfig()
            activeDofs = self.solver.getActiveDofs()
            for k in activeDofs:
                if q[k] < tempqmin[k] or q[k] > tempqmax[k]:
                    #the IK solver normalizer doesn't care about absolute
                    #values for joints that wrap around 2pi
                    if tempqmin[k] <= q[k] + 2 * math.pi and q[
                            k] + 2 * math.pi <= tempqmax[k]:
                        q[k] += 2 * math.pi
                    elif tempqmin[k] <= q[k] - 2 * math.pi and q[
                            k] - 2 * math.pi <= tempqmax[k]:
                        q[k] -= 2 * math.pi
                    else:
                        print(
                            "CartesianDriveSolver: Warning, result from IK solve is out of bounds: index",
                            k, ",", tempqmin[k], "<=", q[k], "<=", tempqmax[k])
                        q[k] = max(min(q[k], tempqmax[k]), tempqmin[k])
            self.robot.setConfig(q)

            #now evaluate quality of the solve
            errAfter = self.solver.getResidual()
            qualityAfter = vectorops.norm(errAfter)
            if qualityAfter > quality0:
                #print("CartesianDriveSolver: Solve failed: original configuration was better:",quality0,"vs",qualityAfter)
                #print("  solver result was",res,"increment",amount)
                res = False
            elif qualityAfter < quality0 - 1e-8:
                res = True

            if res:
                #success!
                for k in activeDofs:
                    qout[k] = q[k]
                    assert tempqmin[k] <= q[k] and q[k] <= tempqmax[k]

                #now advance the driven transforms
                #figure out how much to drive along screw
                numerator = 0  # this will get sum of distance * screws
                denominator = 0  # this will get sum of |screw|^2 for all screws
                #result will be numerator / denominator
                achievedTransforms = [
                    (l.getTransform()[0], l.getWorldPosition(ofs))
                    for l, ofs in zip(robotLinks, self.endEffectorOffsets)
                ]
                #TODO: get transforms relative to baseLink
                for i in range(len(self.links)):
                    if vel[i] is not None:
                        trel = vectorops.sub(achievedTransforms[i][1],
                                             self.driveTransforms[i][1])
                        vellen = vectorops.norm(vel[i])
                        axis = vectorops.div(vel[i], max(vellen, 1e-8))
                        ut = vellen
                        tdistance = vectorops.dot(trel, axis)
                        tdistance = min(max(tdistance, 0.0), dt * vellen)
                        numerator += ut * tdistance
                        denominator += ut**2
                    if angVel[i] is not None:
                        Rrel = so3.mul(achievedTransforms[i][0],
                                       so3.inv(self.driveTransforms[i][0]))
                        vellen = vectorops.norm(angVel[i])
                        angVelRel = so3.apply(
                            so3.inv(self.driveTransforms[i][0]), angVel[i])
                        rotaxis = vectorops.div(angVelRel, max(vellen, 1e-8))
                        Rdistance = axis_rotation_magnitude(Rrel, rotaxis)
                        Rdistance = min(max(Rdistance, 0.0), dt * vellen)
                        uR = vellen
                        numerator += uR * Rdistance
                        denominator += uR**2

                distance = numerator / max(denominator, 1e-8)

                #computed error-minimizing distance along screw motion
                for i in range(len(self.links)):
                    if vel[i] is not None:
                        self.driveTransforms[i][1] = vectorops.madd(
                            self.driveTransforms[i][1], vel[i], distance)
                    else:
                        self.driveTransforms[i][1] = achievedTransforms[i][1]
                    if angVel[i] is not None:
                        Rincrement = so3.from_moment(
                            vectorops.mul(angVel[i], distance))
                        self.driveTransforms[i][0] = normalize_rotation(
                            so3.mul(Rincrement, self.driveTransforms[i][0]))
                    else:
                        self.driveTransforms[i][0] = achievedTransforms[i][0]

                if math.ceil(distance / dt * 10) < math.floor(
                        self.driveSpeedAdjustment * 10):
                    self.driveSpeedAdjustment -= 0.1
                    self.driveSpeedAdjustment = max(self.driveSpeedAdjustment,
                                                    0.0)
                elif not anyFailures:
                    #increase drive velocity
                    if self.driveSpeedAdjustment < 1.0:
                        self.driveSpeedAdjustment += 0.1
                        self.driveSpeedAdjustment = min(
                            1.0, self.driveSpeedAdjustment)

                return (distance / dt, qout)
            else:
                #IK failed: try again with a slower speed adjustment
                anyFailures = True
                self.driveSpeedAdjustment -= 0.1
                if self.driveSpeedAdjustment <= 1e-8:
                    self.driveSpeedAdjustment = 0.0
                    break
        #no progress
        return (-1, qcur)
示例#16
0
def run_poking_ellipse_probe(config,tableHeight,probeLength,forceLimit,dt,moveStep,shortServoTime,longServoTime,
								IKErrorTolerence,maxDev,EEZLimit,probe_transform,point_probe_to_local,world,res,
								robot,link,CONTROLLER,collider,intermediateConfig):
	"""
	this is the main function of poking object. - point probe
	"""
	########################## Read In the pcd ######################################
	points, normals = load_pcd(config.exp_path+'exp_'+str(config.exp_number)+'/probePcd.txt')
	
	# control interface
	if CONTROLLER == 'physical':
		robotControlApi = UR5WithGripperController(host=config.robot_host,gripper=False)
		robotControlApi.start()
		time.sleep(2)
	print '---------------------robot started -----------------------------'

	## Record some home configuration
	intermediateConfig = config.intermediateConfig
	intermediateConfig = intermediateConfig

	if CONTROLLER == "physical":
		constantVServo(robotControlApi,4,intermediateConfig,dt)#controller format

	robot.setConfig(controller_2_klampt(robot,intermediateConfig))
	print '---------------------at home configuration -----------------------------'

	if CONTROLLER == 'debugging':
		differences=[]
		print('[*]Debug: Poking process start!')

		for i in range(len(points)):
			print('point %d, pos: %s, normals: %s'%(i,points[i],normals[i]))

			#robotCurrentConfig=intermediateConfig # TODO: compare to the intermediateConfig, I comment it 
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0)) #get unit vector in the direction '- normals'

			## perform IK
			local_NY_UnitV=vectorops.unit(vectorops.cross([0,1,0],approachVector))			
			pt1=goalPosition
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength)) # use 1m in normals direction.			
			pt3=vectorops.add(pt1,local_NY_UnitV)

			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],maxDev,
											IKErrorTolerence,EEZLimit,collider,use_collision_detect=True,use_ik_detect=True)
			differences.append(difference)
			print('difference: %f'%difference)

			### now start colecting data..
			travel = 0.0
			stepVector = vectorops.mul(approachVector,moveStep)
			
			while travel<0.0001: #just try 0.1mm?
				pt1=vectorops.add(pt1,stepVector)
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
				pt3=vectorops.add(pt1,local_NY_UnitV)
				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],maxDev,
												IKErrorTolerence,EEZLimit,collider,use_const=False)
				travel = travel + moveStep
				
			### move the probe away, note: a bit different to physical mode
			pt1=vectorops.add(points[i],vectorops.mul(approachVector,-0.05))  ## move the probe 5 cm from the object surface
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
			pt3=vectorops.add(pt1,local_NY_UnitV)
			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],maxDev,
											IKErrorTolerence,EEZLimit,collider)

			### move back to intermediate config
			robot.setConfig(controller_2_klampt(robot,intermediateConfig))
		
		print('[*]Debug: Poking process done, with max difference:%f'%max(differences))
		
		vis.show()
		while vis.shown():
			time.sleep(1.0)

	elif CONTROLLER == 'physical':
		######################################## Ready to Take Measurements ################################################
		input('[!]Warning: There are %d poking point, Robot act!:'%len(points))
		point_list = range(65,120) #64
		#point_list = random.sample(range(0,94),94)

		#finish_list = [0,1,4,9,10,11,12,13,14,15,17,18,19,20,25,26,28,30,33,34,35,37,42,43,44,46,47,50,51,53,54,57,58,59,64,69,72,73,74,75,76,77,78,79,81,83,86,95]
		#point_list = [x for x in point_list if x not in finish_list]
		
		point_list = [64]
		
		for i in point_list:	
			print('point %d, pos: %s, normals: %s'%(i,points[i],normals[i]))
			
			#init record file
			forceData=open(config.exp_path+'exp_'+str(config.exp_number)+'/ellipse/force_'+str(i)+'.txt','w')
			torqueData=open(config.exp_path+'exp_'+str(config.exp_number)+'/ellipse/torque_'+str(i)+'.txt','w')

			#init the backforward distance
			travel = -0.018

			robotCurrentConfig=robotControlApi.getConfig()
			robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
			#calculate start position
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0))
			#### Make sure no contact, backup 0.01m
			local_NY_UnitV=vectorops.unit(vectorops.cross([0,1,0],approachVector))

			pt1=vectorops.add(goalPosition,vectorops.mul(approachVector,travel))
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))			
			pt3=vectorops.add(pt1,local_NY_UnitV)

			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime-1,dt,
											use_ik_detect=False,use_collision_detect=False)

			time.sleep(0.2)

			## Zero the sensor before straight line push
			#
			# Note that the force is recorded in the global frame..
			# And the global frame has x and y axis flipped w.r.t the URDF....

			counter = 0.0
			totalF = [0,0,0]
			totalTorque = [0,0,0]

			startTime=time.time()
			while (time.time()-startTime) < 1: # use 1s to cal the Force
				totalF = vectorops.add(totalF,robotControlApi.getWrench()[0:3])
				totalTorque = vectorops.add(totalTorque,robotControlApi.getWrench()[3:6])
				counter = counter + 1.0
				time.sleep(dt)
			forceBias = vectorops.mul(totalF,1.0/float(counter)) # when probe no touch the obj, F_avr = sum(F)/n
			torqueBias = vectorops.mul(totalTorque,1.0/float(counter))


			### now start collecting data..
			# Force direction x, y inverse, refer to correct force.py
			wrench = robotControlApi.getWrench()
			Force = fix_direction(vectorops.sub(wrench[0:3],forceBias))
			Force_normal = math.fabs(vectorops.dot(Force,approachVector)) #|F||n|cos(theta) = F dot n, set it >= 0 
			Torque = vectorops.sub(wrench[3:6],torqueBias)
			Torque = fix_direction(Torque)
						
			forceHistory = [Force]
			torqueHistory = [Torque]			
			force_normalHistory = [Force_normal]
			displacementHistory = [travel]
			stepVector = vectorops.mul(approachVector,moveStep)

			while Force_normal < forceLimit:
				robotCurrentConfig=robotControlApi.getConfig()
				robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
				pt1=vectorops.add(pt1,stepVector)
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
				pt3=vectorops.add(pt1,local_NY_UnitV)
				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
												maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime,dt,
												use_const=False,use_ik_detect=False)
				time.sleep(dt)

				Force = fix_direction(vectorops.sub(robotControlApi.getWrench()[0:3],forceBias))
				Force_normal = math.fabs(vectorops.dot(Force,approachVector))
				Torque = vectorops.sub(robotControlApi.getWrench()[3:6],torqueBias)

				travel = travel + moveStep

				forceHistory.append([Force[0],Force[1],Force[2]])
				torqueHistory.append([Torque[0],Torque[1],Torque[2]])					
				force_normalHistory.append(Force_normal)
				displacementHistory.append(travel)
			
			#record all the data in 2 files, one N*2 containts all the force data collected at various locations, another
			#file specifies the number of datapoints at each detected point
			for (f,fn,d) in zip(forceHistory,force_normalHistory,displacementHistory):
				forceData.write(str(f[0])+' '+str(f[1])+' '+str(f[2])+' '+str(fn)+' '+str(d)+'\n')		
			for (t,d) in zip(torqueHistory,displacementHistory):
				torqueData.write(str(t[0])+' '+str(t[1])+' '+str(t[2])+' '+str(d)+'\n')
			forceData.close()
			torqueData.close()

			### move the probe away
			robotCurrentConfig=robotControlApi.getConfig()
			robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
			pt1=vectorops.add(points[i],vectorops.mul(approachVector,-0.10))  ## move the probe 5 cm from the object surface
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
			pt3=vectorops.add(pt1,local_NY_UnitV)
			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,shortServoTime,dt,
											use_ik_detect=False)
			
			#constantVServo(robotControlApi,longServoTime,intermediateConfig,dt)

			print'----------------------- pt '+str(i)+' completed -------------------------------'
		
		#### move back to intermediate config
		constantVServo(robotControlApi,shortServoTime,intermediateConfig,dt)	
		robotControlApi.stop()
示例#17
0
def run_poking_line_probe(config,tableHeight,probeLength,forceLimit,dt,moveStep,shortServoTime,longServoTime,
							IKErrorTolerence,maxDev,EEZLimit,probe_transform,point_probe_to_local,world,res,
							robot,link,CONTROLLER,collider,intermediateConfig):
	"""
	this is the main function of poking object. - line probe
	"""
	# reconstruct probepcd.txt
	if input('[*]Reconstruct probe pcd?') == 1:
		theta_list_num = input('---need theta list number: ')
		reconstruct_pcd(config.exp_path+'exp_'+str(config.exp_number)+'/probePcd.txt',
						config.exp_path+'exp_'+str(config.exp_number)+'/probePcd_theta.txt',
						theta_list_num)
		print('---New probe list done')

	# Read In the pcd
	points, normals, theta_list, theta, pti = load_pcd(config.exp_path+'exp_'+str(config.exp_number)+'/probePcd_theta.txt', pcdtype='xyzrgbntheta')
	
	# control interface
	if CONTROLLER == 'physical':
		robotControlApi = UR5WithGripperController(host=config.robot_host,gripper=False)
		robotControlApi.start()
		time.sleep(2)
		print '---------------------robot started -----------------------------'
		constantVServo(robotControlApi,4,intermediateConfig,dt)#controller format

	# set in simul model
	robot.setConfig(controller_2_klampt(robot,intermediateConfig))
	print '---------------------at home configuration -----------------------------'

	if CONTROLLER == 'debugging':
		differences=[]
		print('[*]Debug: Poking process start')

		i = 0 # use this to catch points
		pti_ = pti[i]
		while(i < len(points)):
			robotCurrentConfig=intermediateConfig
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0)) #get unit vector in the direction '- normals'
			_pti = pti_

			if pti[i] == _pti:
				print('point %d, pos: %s, normals: %s, theta: %s, -> %f'%(i,points[i],normals[i],theta_list[i],theta[i]))
				## perform IK				
				local_NY_UnitV = vectorops.unit(back_2_line(approachVector,theta_list[i])) # the probe's line direction

				pt1=goalPosition
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength)) # use 1m in normals direction.				
				pt3=vectorops.add(pt1,local_NY_UnitV)

				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
												maxDev,IKErrorTolerence,EEZLimit,collider,use_collision_detect=False,use_ik_detect=True)
				differences.append(difference)
				print('difference: %f'%difference)

				### now start colecting data..
				travel = 0.0
				stepVector = vectorops.mul(approachVector,moveStep)
				
				while travel<0.0001:
					robotCurrentConfig=klampt_2_controller(robot.getConfig())
					pt1=vectorops.add(pt1,stepVector)
					pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
					pt3=vectorops.add(pt1,local_NY_UnitV)

					[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
													maxDev,IKErrorTolerence,EEZLimit,collider,use_collision_detect=False)
					travel = travel + moveStep

				### move the probe away, note: a bit different to physical mode
				robotCurrentConfig=klampt_2_controller(robot.getConfig())
				pt1=vectorops.add(points[i],vectorops.mul(approachVector,-0.05))  ## move the probe 5 cm from the object surface
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
				pt3=vectorops.add(pt1,local_NY_UnitV)

				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
												maxDev,IKErrorTolerence,EEZLimit,collider,use_collision_detect=False)

				### move back to intermediate config
				robot.setConfig(controller_2_klampt(robot,intermediateConfig))

				i = i + 1 # important
			else:
				pti_ = pti[i]
		
		print('[*]Debug: Poking process done, with max difference:%f'%max(differences))
		
		vis.show()
		while vis.shown():
			time.sleep(1.0)

	elif CONTROLLER == 'physical':
		exe_number = input('There are %d poking point, go?'%len(points))

		start_i = 0 #72,93,94,97,99,100,101,108,116,125,128,147,148,150,151,152,189,194~197,207~210   !40,37,67,68 -> 111 112 113 120 121 122 201 206
 		end_i = 1 #len(points)
		i = start_i # use this to catch points, set manully! # TODO:
		pti_ = pti[i]
		
		probe_list = random.sample(range(282),282) #18,15
		finish_list= range(16)+range(17,21)+range(25,44)+range(45,51)+range(52,57)+[58,59,60,63,67,68,71,73,75,76,78]+range(81,96)\
					+[97,99,101,103,104,108,110,112,114,115,117,118,120,124,125,128,129,130]+range(132,138)+[141,142,144,147,149,150,151]+range(153,156)\
					+[159,160,161,167,168,170,172,175,176,177,178]+range(180,186)\
					+[189,192,195,196,199,200,201,203]+range(204,210)+range(211,217)+[219]+range(221,229)+range(230,236)+range(237,241)\
					+range(244,250)+[251]+range(254,261)+[262]+range(264,276)+range(277,282)
		probe_list = [x for x in probe_list if x not in finish_list] +[227]

		probe_list = [95]
		
		for i in probe_list:
			print('point %d, pos: %s, normals: %s, theta: %s, -> %f'%(i,points[i],normals[i],theta_list[i],theta[i]))
			
			robotCurrentConfig=robotControlApi.getConfig()
			robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
			# calculate start position
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0))

			# init record file
			forceData=open(config.exp_path+'exp_'+str(config.exp_number)+'/line/force_'+str(i)+'.txt','w')
			torqueData=open(config.exp_path+'exp_'+str(config.exp_number)+'/line/torque_'+str(i)+'.txt','w')

			travel = -0.025

			## perform IK
			local_NY_UnitV = vectorops.unit(back_2_line(approachVector,theta_list[i])) # the probe's line direction
			#### Make sure no contact, backup 0.01m
			pt1=vectorops.add(goalPosition,vectorops.mul(approachVector,travel))
			pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength)) # use 1m in normals direction.				
			pt3=vectorops.add(pt1,local_NY_UnitV)
			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
										maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,shortServoTime,dt) #TODO:
			time.sleep(0.2)

			# Zero the sensor before straight line push, Note that the force is recorded in the global frame..
			counter = 0.0
			totalF = [0,0,0]
			totalTorque = [0,0,0]
			startTime=time.time()
			while (time.time()-startTime) < 1: # use 1s to cal the Force
				totalF = vectorops.add(totalF,robotControlApi.getWrench()[0:3])
				totalTorque = vectorops.add(totalTorque,robotControlApi.getWrench()[3:6])
				counter = counter + 1.0
				time.sleep(dt)
			forceBias = vectorops.mul(totalF,1.0/float(counter)) # when probe no touch the obj, F_avr = sum(F)/n
			torqueBias = vectorops.mul(totalTorque,1.0/float(counter))

			### now start collecting data..
			wrench = robotControlApi.getWrench()
			Force = vectorops.sub(wrench[0:3],forceBias)
			Torque = vectorops.sub(wrench[3:6],torqueBias)
			Force_normal = math.fabs(vectorops.dot(Force,approachVector)) #|F||n|cos(theta) = F dot n, set it >= 0 
			
			local_Z_UnitV = vectorops.cross(normals[i],local_NY_UnitV)
			Torque_normal = vectorops.dot(Torque,local_Z_UnitV) #TODO:
			
			forceHistory = [Force]			
			force_normalHistory = [Force_normal]
			torqueHistory = [Torque]
			torque_normalHistory = [Torque_normal]

			displacementHistory = [travel]
			stepVector = vectorops.mul(approachVector,moveStep)

			while Force_normal < forceLimit:
				robotCurrentConfig=robotControlApi.getConfig()
				robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
				pt1=vectorops.add(pt1,stepVector)
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
				pt3=vectorops.add(pt1,local_NY_UnitV)

				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
										maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime,dt,use_const=False)
				time.sleep(dt)

				Force = vectorops.sub(robotControlApi.getWrench()[0:3],forceBias)
				Torque = vectorops.sub(robotControlApi.getWrench()[3:6],torqueBias)
				Force_normal = math.fabs(vectorops.dot(Force,approachVector))

				local_Z_UnitV = vectorops.cross(normals[i],local_NY_UnitV)
				Torque_normal = vectorops.dot(Torque,local_Z_UnitV)

				travel = travel + moveStep

				forceHistory.append([Force[0],Force[1],Force[2]])				
				force_normalHistory.append(Force_normal)
				torqueHistory.append([Torque[0],Torque[1],Torque[2]])				
				torque_normalHistory.append(Torque_normal)

				displacementHistory.append(travel)
			
			#record all the data in 2 files, one N*2 containts all the force data collected at various locations, another
			#file specifies the number of datapoints at each detected point				
			for (f,fn,d) in zip(forceHistory,force_normalHistory,displacementHistory):
				forceData.write(str(f[0])+' '+str(f[1])+' '+str(f[2])+' '+str(fn)+' '+str(d)+'\n')
			
			for (t,tn,d) in zip(torqueHistory,torque_normalHistory,displacementHistory):
				torqueData.write(str(t[0])+' '+str(t[1])+' '+str(t[2])+' '+str(tn)+' '+str(d)+'\n')

			### move the probe away, sometimes z up 5cm is better than normal direction up 5cm...
			pt1=vectorops.add(pt1,[0,0,0.05])  ## move the probe 10 cm up-z-axis, find another point
			pt2=vectorops.add(pt2,[0,0,0.05])
			pt3=vectorops.add(pt3,[0,0,0.05])
			[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,shortServoTime-1,dt)

			constantVServo(robotControlApi,longServoTime,intermediateConfig,dt)#TODO:
			# close record file for point i
			forceData.close()
			torqueData.close()
			print'----------------------- pt '+str(i)+' completed -------------------------------'
		'''
		while(i < end_i):
					
			robotCurrentConfig=robotControlApi.getConfig()
			robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
			# calculate start position
			goalPosition=deepcopy(points[i])
			approachVector=vectorops.unit(vectorops.mul(normals[i],-1.0))

			# init record file
			forceData=open(config.exp_path+'exp_'+str(config.exp_number)+'/line/force_'+str(i)+'.txt','w')
			torqueData=open(config.exp_path+'exp_'+str(config.exp_number)+'/line/torque_'+str(i)+'.txt','w')

			_pti = pti_
			if pti[i] == _pti:
				print('point %d, pos: %s, normals: %s, theta: %s, -> %f'%(i,points[i],normals[i],theta_list[i],theta[i]))
				
				travel = -0.015

				## perform IK
				local_NY_UnitV = vectorops.unit(back_2_line(approachVector,theta_list[i])) # the probe's line direction
				#### Make sure no contact, backup 0.01m
				pt1=vectorops.add(goalPosition,vectorops.mul(approachVector,travel))
				pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength)) # use 1m in normals direction.				
				pt3=vectorops.add(pt1,local_NY_UnitV)
				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime-1,dt) #TODO:
				time.sleep(0.2)

				# Zero the sensor before straight line push, Note that the force is recorded in the global frame..
				counter = 0.0
				totalF = [0,0,0]
				totalTorque = [0,0,0]
				startTime=time.time()
				while (time.time()-startTime) < 1: # use 1s to cal the Force
					totalF = vectorops.add(totalF,robotControlApi.getWrench()[0:3])
					totalTorque = vectorops.add(totalTorque,robotControlApi.getWrench()[3:6])
					counter = counter + 1.0
					time.sleep(dt)
				forceBias = vectorops.mul(totalF,1.0/float(counter)) # when probe no touch the obj, F_avr = sum(F)/n
				torqueBias = vectorops.mul(totalTorque,1.0/float(counter))

				### now start collecting data..
				wrench = robotControlApi.getWrench()
				Force = vectorops.sub(wrench[0:3],forceBias)
				Torque = vectorops.sub(wrench[3:6],torqueBias)
				Force_normal = math.fabs(vectorops.dot(Force,approachVector)) #|F||n|cos(theta) = F dot n, set it >= 0 
				
				local_Z_UnitV = vectorops.cross(normals[i],local_NY_UnitV)
				Torque_normal = vectorops.dot(Torque,local_Z_UnitV) #TODO:
				
				forceHistory = [Force]			
				force_normalHistory = [Force_normal]
				torqueHistory = [Torque]
				torque_normalHistory = [Torque_normal]

				displacementHistory = [travel]
				stepVector = vectorops.mul(approachVector,moveStep)

				while Force_normal < forceLimit:
					robotCurrentConfig=robotControlApi.getConfig()
					robot.setConfig(controller_2_klampt(robot,robotCurrentConfig))
					pt1=vectorops.add(pt1,stepVector)
					pt2=vectorops.add(pt1,vectorops.mul(approachVector,1.0-probeLength))
					pt3=vectorops.add(pt1,local_NY_UnitV)

					[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
											maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,longServoTime,dt,use_const=False)
					time.sleep(dt)

					Force = vectorops.sub(robotControlApi.getWrench()[0:3],forceBias)
					Torque = vectorops.sub(robotControlApi.getWrench()[3:6],torqueBias)
					Force_normal = math.fabs(vectorops.dot(Force,approachVector))

					local_Z_UnitV = vectorops.cross(normals[i],local_NY_UnitV)
					Torque_normal = vectorops.dot(Torque,local_Z_UnitV)

					travel = travel + moveStep

					forceHistory.append([Force[0],Force[1],Force[2]])				
					force_normalHistory.append(Force_normal)
					torqueHistory.append([Torque[0],Torque[1],Torque[2]])				
					torque_normalHistory.append(Torque_normal)

					displacementHistory.append(travel)
				
				#record all the data in 2 files, one N*2 containts all the force data collected at various locations, another
				#file specifies the number of datapoints at each detected point				
				for (f,fn,d) in zip(forceHistory,force_normalHistory,displacementHistory):
					forceData.write(str(f[0])+' '+str(f[1])+' '+str(f[2])+' '+str(fn)+' '+str(d)+'\n')
				
				for (t,tn,d) in zip(torqueHistory,torque_normalHistory,displacementHistory):
					torqueData.write(str(t[0])+' '+str(t[1])+' '+str(t[2])+' '+str(tn)+' '+str(d)+'\n')

				### move the probe away, sometimes z up 5cm is better than normal direction up 5cm...
				pt1=vectorops.add(pt1,[0,0,0.05])  ## move the probe 10 cm up-z-axis, find another point
				pt2=vectorops.add(pt2,[0,0,0.05])
				pt3=vectorops.add(pt3,[0,0,0.05])
				[robot,difference] = robot_move(CONTROLLER,world,robot,link,point_probe_to_local,[pt1,pt2,pt3],
												maxDev,IKErrorTolerence,EEZLimit,collider,robotControlApi,shortServoTime-0.5,dt)

				#constantVServo(robotControlApi,longServoTime,intermediateConfig,dt)#TODO:
				i = i + 1
				# close record file for point i
				forceData.close()
				torqueData.close()
				print'----------------------- pt '+str(i)+' completed -------------------------------'
			
			else:
				# up 10cm is faster but not good.
				# since the points are close, no need to go back home
			
				constantVServo(robotControlApi,longServoTime,intermediateConfig,dt)
				pti_ = pti[i]
		'''
			
		#### move back to intermediate config
		constantVServo(robotControlApi,shortServoTime,intermediateConfig,dt)
		# finish all points
		robotControlApi.stop()
示例#18
0
def cal_curvature(pcdSegmented):
    NofPts = len(pcdSegmented.points)
    NofNN = 30
    searchR = 0.01  #the points are 2mm apart...

    pcdTree = KDTreeFlann(pcdSegmented)
    curvatures = []

    print 'calculating curvatures......'
    for i in range(len(pcdSegmented.points)):
        #for i in [0]:
        [k, idx, _] = pcdTree.search_knn_vector_3d(pcdSegmented.points[i],
                                                   NofNN + 1)
        #[k,idx,_] = pcdTree.search_radius_vector_3d(pcdSegmented.points[i],searchR)
        #k is the total Number, while idx is the list of indices
        #for debugging
        #for ii in idx:
        #	pcdSegmente.colors[ii] = [0,1,0]
        #draw_geometries([pcdSegmented])

        #if k < 3.5:
        #	[k,idx,_] = pcdTree.search_knn_vector_3d(pcdSegmented.points[i],NofNN+1)
        nearbyPts = np.asarray(pcdSegmented.points)[idx[1:], :]
        nearbyPtsNormal = np.asarray(pcdSegmented.normals)[idx[1:], :]

        normalCurvatures = []
        ## Define the local coordinates
        N = vectorops.unit(pcdSegmented.normals[i])  # also the "z"
        Y = vectorops.cross(N, [1, 0, 0])  # pq = vectorops.(q,p)
        X = vectorops.cross(Y, N)
        MMatrix = []
        for j in range(k - 1):
            #estimate the point normal, in Local corrdinate
            qGlobal = vectorops.sub(nearbyPts[j], pcdSegmented.points[i])
            qLocal = [
                vectorops.dot(qGlobal, X),
                vectorops.dot(qGlobal, Y),
                vectorops.dot(qGlobal, N)
            ]
            MGlobal = nearbyPtsNormal[j]
            MLocal = [
                vectorops.dot(MGlobal, X),
                vectorops.dot(MGlobal, Y),
                vectorops.dot(MGlobal, N)
            ]
            [x_i, y_i, z_i] = qLocal
            [n_xi, n_yi, n_zi] = MLocal

            #print x_i,n_xi,y_i,n_yi
            n_xy = (x_i * n_xi + y_i * n_yi) / math.sqrt(x_i * x_i + y_i * y_i)
            #print n_xy
            k_i_n = -(n_xy) / (math.sqrt(n_xy * n_xy + n_zi * n_zi) +
                               math.sqrt(x_i * x_i + y_i * y_i))
            normalCurvatures.append(k_i_n)

            ## calculate the M matrix
            pQ = [qLocal[0], qLocal[1], 0]
            angle = np.arccos(
                np.dot(X, pQ) / (np.linalg.norm(X) * np.linalg.norm(pQ)))
            row = [
                math.cos(angle) * math.cos(angle),
                2 * math.cos(angle) * math.sin(angle),
                math.sin(angle) * math.sin(angle)
            ]
            MMatrix.append(row)
        #perform least squres fitting
        tmp = np.dot(np.transpose(MMatrix), MMatrix)
        tmp2 = np.dot(np.linalg.inv(tmp), np.transpose(MMatrix))
        x = tmp2.dot(normalCurvatures)
        eigenValues, v = np.linalg.eig([[x[0], x[1]], [x[1], x[2]]])
        curvatures.append(vectorops.norm_L1(eigenValues))
        #print vectorops.norm_L1(eigenValues)
        print 'progress', float(i) / float(NofPts)

    print "max and min of curvatures: ", np.max(curvatures), np.min(curvatures)
    return curvatures
示例#19
0
	def find_target(self):
		self.current_target=self.waiting_list[0]
		best_p=self.sim.world.rigidObject(self.current_target).getTransform()[1]
		self.current_target_pos=best_p
		for i in self.waiting_list:
			p=self.sim.world.rigidObject(i).getTransform()[1]
			# print i,p[2],vectorops.distance([0,0],[p[0],p[1]])
			if i not in self.failedpickup:
				if p[2]>best_p[2]+0.05:
					self.current_target=i
					self.current_target_pos=p
					# print 'higher is easier!'
					best_p=p
				elif p[2]>best_p[2]-0.04 and vectorops.distance([0,0],[p[0],p[1]])<vectorops.distance([0,0],[best_p[0],best_p[1]]):
					self.current_target=i
					self.current_target_pos=p		
					best_p=p
				elif self.current_target in self.failedpickup:
					self.current_target=i
					self.current_target_pos=p		
					best_p=p
		d_y=-0.02
		face_down=face_down_forward
		self.tooclose = False;
		if best_p[1]>0.15:
			d_y=-0.02
			face_down=face_down_backward
			self.tooclose = True;
			print 'too close to the wall!!'
		elif best_p[1]<-0.15:
			d_y=0.02
			print best_p
			self.tooclose = True;
			print 'too close to the wall!!'
		#here is hardcoding the best relative position for grasp the ball

		target=(face_down,vectorops.add(best_p,[0,d_y,0.14]))
		if self.tooclose:
			if best_p[0]<0:
				self.boxside=boxleft
				aready_pos=start_pos_left
			else:
				self.boxside=boxright
				aready_pos=start_pos_right
			aready_pos[1][0]=best_p[0]
			balllocation = best_p
			handballdiff = vectorops.sub(aready_pos[1],best_p)
			axis = vectorops.unit(vectorops.cross(handballdiff,aready_pos[1]))
			axis = (1,0,0)
			if best_p[1]>0:
				axis=(-1,0,0)
			angleforaxis = -1*math.acos(vectorops.dot(aready_pos[1],handballdiff)/vectorops.norm(aready_pos[1])/vectorops.norm(handballdiff))
			angleforaxis = so2.normalize(angleforaxis)
			#if angleforaxis>math.pi:
			#	angleforaxis=angleforaxis-2*math.pi
			adjR = so3.rotation(axis, angleforaxis)
			print balllocation
			print vectorops.norm(aready_pos[1]),vectorops.norm(handballdiff),angleforaxis
			target=(adjR,vectorops.add(best_p,vectorops.div(vectorops.unit(handballdiff),5)))

		# print self.current_target	
		# print 'find target at:',self.current_target_pos	
		return target