sinusoid.py
Go to the documentation of this file.
00001 import roslib
00002 roslib.load_manifest("phantom_omni")
00003 import rospy
00004 import tf
00005 import tf.transformations as tr
00006 
00007 from geometry_msgs.msg import PoseStamped
00008 from geometry_msgs.msg import Pose
00009 from geometry_msgs.msg import Wrench
00010 
00011 import math
00012 import numpy as np
00013 
00014 def tf2mat(tf_trans):
00015     (trans, rot) = tf_trans
00016     return np.matrix(tr.translation_matrix(trans)) * np.matrix(tr.quaternion_matrix(rot))
00017 
00018 def mat2pose(m):
00019     trans = tr.translation_from_matrix(m)
00020     rot   = tr.quaternion_from_matrix(m)
00021     p = Pose()
00022     p.position.x = trans[0]
00023     p.position.y = trans[1]
00024     p.position.z = trans[2]
00025     p.orientation.x = rot[0]
00026     p.orientation.y = rot[1]
00027     p.orientation.z = rot[2]
00028     p.orientation.w = rot[3]
00029     return p
00030 
00031 rospy.init_node("omni_potential_well")
00032 wpub = rospy.Publisher('force_feedback', Wrench)
00033 r = rospy.Rate(1000)
00034 
00035 #listener = tf.TransformListener()
00036 #listener.waitForTransform("/world", "/omni1_link6", rospy.Time(), rospy.Duration(4.0))
00037 #listener.waitForTransform("/world", "/sensable", rospy.Time(), rospy.Duration(4.0))
00038 print 'running.'
00039 
00040 well_center = None
00041 angle = 0.;
00042 while not rospy.is_shutdown():
00043     #w_T_6 = tf2mat(listener.lookupTransform('/world', '/omni1_link6', rospy.Time(0)))
00044     #qm = np.matrix(tr.quaternion_matrix(tr.quaternion_from_euler(0, math.pi, 0)))
00045     #tm = np.matrix(tr.translation_matrix([-.134, 0, 0]))
00046     #tip_6 = tm * qm
00047     #tip_world = w_T_6 * tip_6
00048     #pos = np.matrix(tr.translation_from_matrix(tip_world)).T
00049 
00050     #force_world = (w_T_6[0:3,0:3] * np.matrix([-2., 0, 0]).T)
00051     #trans, rot = listener.lookupTransform('/sensable', '/world', rospy.Time(0))
00052     #quat_mat = np.matrix(tr.quaternion_matrix(rot))
00053     #force_sensable = quat_mat[0:3, 0:3] * force_world
00054 
00055     wr = Wrench()
00056     angle = np.radians(.3) + angle
00057     wr.force.x = 0#force_sensable[0]
00058     wr.force.y = 0#force_sensable[1]
00059     wr.force.z = np.sin(angle) * 3#force_sensable[2]
00060     print wr.force.z
00061     wpub.publish(wr)
00062     r.sleep()
00063 
00064 
00065 
00066 
00067 
00068 
00069 
00070 
00071 
00072 
00073 
00074 
00075 
00076 
00077 
00078 
00079 
00080 
00081 
00082 
00083 
00084 
00085 
00086 
00087 
00088 
00089 
00090 
00091     #ps = PoseStamped()
00092     #ps.header.frame_id = 'sensable'
00093     #ps.header.stamp = rospy.get_rostime()
00094     #ps.pose = mat2pose(tip_world)
00095     #pub.publish(ps)
00096 
00097 
00098     #print force_sensable.T
00099 
00100 
00101     #if well_center == None:
00102     #    well_center = pos
00103     #else:
00104     #    trans, rot = listener.lookupTransform('/world', '/sensable', rospy.Time(0))
00105     #    quat_mat = np.matrix(tr.quaternion_matrix(rot))
00106 
00107     #    dir = -(well_center - pos)
00108     #    mag = np.linalg.norm(dir)
00109     #    dir = dir / mag
00110     #    mag = np.min(mag*10., 5)
00111 
00112     #    print dir.T, mag
00113     #    force_world = dir * mag
00114     #    force_sensable = quat_mat[0:3, 0:3] * force_world
00115 
00116     #    wr = Wrench()
00117     #    wr.force.x = force_sensable[0]
00118     #    wr.force.y = force_sensable[1]
00119     #    wr.force.z = force_sensable[2]
00120     #    wpub.publish(wr)
00121 
00122 
00123 
00124 
00125 
00126 
00127 
00128 
00129 
00130 
00131 
00132 
00133 
00134 
00135 
00136 
00137 
00138 
00139 
00140 
00141 
00142 
00143 
00144 
00145 
00146 
00147 
00148 
00149 
00150         
00151 
00152     #ps = PoseStamped()
00153     #ps.header.frame_id = 'world'
00154     #ps.header.stamp = rospy.get_rostime()
00155     #ps.pose = mat2pose(tip_world)
00156     #pub.publish(ps)
00157     #r.sleep()
00158 
00159     #Input force in link6's frame
00160     #Output force in omni base frame
00161     #wr = Wrench()
00162     #wr.force.x = np.random.rand()*2 - 1
00163     #wr.force.y = np.random.rand()*2 - 1
00164     #wr.force.z = np.random.rand()*2 - 1
00165     #wpub.publish(wr)
00166 
00167 
00168 
00169 


phantom_omni
Author(s): Hai Nguyen, Marc Killpack, Chi-Hung King, Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 11:51:14