4 from numpy.random
import random
8 if __name__ ==
'__main__':
12 ik_solver =
IK(
"torso_lift_link",
15 print(
"IK solver uses link chain:")
16 print(ik_solver.link_names)
18 print(
"IK solver base frame:")
19 print(ik_solver.base_link)
21 print(
"IK solver tip link:")
22 print(ik_solver.tip_link)
24 print(
"IK solver for joints:")
25 print(ik_solver.joint_names)
27 print(
"IK solver using joint limits:")
28 lb, up = ik_solver.get_joint_limits()
29 print(
"Lower bound: " + str(lb))
30 print(
"Upper bound: " + str(up))
32 qinit = [0.] * ik_solver.number_of_joints
42 for _
in range(NUM_COORDS):
44 y = random() * 0.6 + -0.3
45 z = random() * 0.7 + -0.35
46 rand_coords.append((x, y, z))
50 num_solutions_found = 0
51 for x, y, z
in rand_coords:
53 sol = ik_solver.get_ik(qinit,
59 call_time = fin_t - ini_t
65 num_solutions_found += 1
66 avg_time = avg_time / NUM_COORDS
69 print "Found " + str(num_solutions_found) +
" of 200 random coords" 70 print "Average IK call time: " + str(avg_time)
75 num_solutions_found = 0
76 brx = bry = brz = 9999.0
77 for x, y, z
in rand_coords:
79 sol = ik_solver.get_ik(qinit,
85 call_time = fin_t - ini_t
91 num_solutions_found += 1
93 avg_time = avg_time / NUM_COORDS
95 print "Found " + str(num_solutions_found) +
" of 200 random coords ignoring orientation" 96 print "Average IK call time: " + str(avg_time)
101 num_solutions_found = 0
102 bx = by = bz = 9999.0
103 brx = bry = brz = 9999.0
104 for x, y, z
in rand_coords:
106 sol = ik_solver.get_ik(qinit,
112 call_time = fin_t - ini_t
114 avg_time += call_time
118 num_solutions_found += 1
120 avg_time = avg_time / NUM_COORDS
123 print "Found " + str(num_solutions_found) +
" of 200 random coords ignoring everything" 124 print "Average IK call time: " + str(avg_time)