00001
00002
00003 from trac_ik_python.trac_ik_wrap import TRAC_IK
00004 import rospy
00005 from numpy.random import random
00006 import time
00007
00008
00009 if __name__ == '__main__':
00010
00011
00012 urdf = rospy.get_param('/robot_description')
00013
00014
00015
00016 ik_solver = TRAC_IK("torso_lift_link",
00017 "r_wrist_roll_link",
00018 urdf,
00019 0.005,
00020 1e-5,
00021 "Speed")
00022 print("Number of joints:")
00023 print(ik_solver.getNrOfJointsInChain())
00024 print("Joint names:")
00025 print(ik_solver.getJointNamesInChain(urdf))
00026 print("Link names:")
00027 print(ik_solver.getLinkNamesInChain())
00028
00029 qinit = [0.] * 7
00030 x = y = z = 0.0
00031 rx = ry = rz = 0.0
00032 rw = 1.0
00033 bx = by = bz = 0.001
00034 brx = bry = brz = 0.1
00035
00036
00037 NUM_COORDS = 200
00038 rand_coords = []
00039 for _ in range(NUM_COORDS):
00040 x = random() * 0.5
00041 y = random() * 0.6 + -0.3
00042 z = random() * 0.7 + -0.35
00043 rand_coords.append((x, y, z))
00044
00045
00046 avg_time = 0.0
00047 num_solutions_found = 0
00048 for x, y, z in rand_coords:
00049 ini_t = time.time()
00050 sol = ik_solver.CartToJnt(qinit,
00051 x, y, z,
00052 rx, ry, rz, rw,
00053 bx, by, bz,
00054 brx, bry, brz)
00055 fin_t = time.time()
00056 call_time = fin_t - ini_t
00057
00058 avg_time += call_time
00059 if sol:
00060
00061
00062 num_solutions_found += 1
00063 avg_time = avg_time / NUM_COORDS
00064
00065 print
00066 print "Found " + str(num_solutions_found) + " of 200 random coords"
00067 print "Average IK call time: " + str(avg_time)
00068 print
00069
00070
00071 avg_time = 0.0
00072 num_solutions_found = 0
00073 brx = bry = brz = 9999.0
00074 for x, y, z in rand_coords:
00075 ini_t = time.time()
00076 sol = ik_solver.CartToJnt(qinit,
00077 x, y, z,
00078 rx, ry, rz, rw,
00079 bx, by, bz,
00080 brx, bry, brz)
00081 fin_t = time.time()
00082 call_time = fin_t - ini_t
00083
00084 avg_time += call_time
00085 if sol:
00086
00087
00088 num_solutions_found += 1
00089
00090 avg_time = avg_time / NUM_COORDS
00091 print
00092 print "Found " + str(num_solutions_found) + " of 200 random coords ignoring orientation"
00093 print "Average IK call time: " + str(avg_time)
00094 print
00095
00096
00097 avg_time = 0.0
00098 num_solutions_found = 0
00099 bx = by = bz = 9999.0
00100 brx = bry = brz = 9999.0
00101 for x, y, z in rand_coords:
00102 ini_t = time.time()
00103 sol = ik_solver.CartToJnt(qinit,
00104 x, y, z,
00105 rx, ry, rz, rw,
00106 bx, by, bz,
00107 brx, bry, brz)
00108 fin_t = time.time()
00109 call_time = fin_t - ini_t
00110
00111 avg_time += call_time
00112 if sol:
00113
00114
00115 num_solutions_found += 1
00116
00117 avg_time = avg_time / NUM_COORDS
00118
00119 print
00120 print "Found " + str(num_solutions_found) + " of 200 random coords ignoring everything"
00121 print "Average IK call time: " + str(avg_time)
00122 print
00123
00124
00125
00126
00127
00128
00129
00130
00131