test_wrapper.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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     # roslaunch pr2_description upload_pr2.launch
00011     # Needed beforehand
00012     urdf = rospy.get_param('/robot_description')
00013     # params of constructor:
00014     # base_link, tip_link, urdf_string, timeout, epsilon, solve_type="Speed"
00015     # solve_type can be: Distance, Speed, Manipulation1, Manipulation2
00016     ik_solver = TRAC_IK("torso_lift_link",
00017                         "r_wrist_roll_link",
00018                         urdf,
00019                         0.005,  # default seconds
00020                         1e-5,  # default epsilon
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     # Generate a set of random coords in the arm workarea approx
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     # Check some random coords with fixed orientation
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         # print "IK call took: " + str(call_time)
00058         avg_time += call_time
00059         if sol:
00060             # print "X, Y, Z: " + str( (x, y, z) )
00061             # print "SOL: " + str(sol)
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     # Check if orientation bounds work
00071     avg_time = 0.0
00072     num_solutions_found = 0
00073     brx = bry = brz = 9999.0  # We don't care about orientation
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         # print "IK call took: " + str(call_time)
00084         avg_time += call_time
00085         if sol:
00086             # print "X, Y, Z: " + str( (x, y, z) )
00087             # print "SOL: " + str(sol)
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     # Check if big position and orientation bounds work
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         # print "IK call took: " + str(call_time)
00111         avg_time += call_time
00112         if sol:
00113             # print "X, Y, Z: " + str( (x, y, z) )
00114             # print "SOL: " + str(sol)
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 # std::vector<double> CartToJnt(const std::vector<double> q_init,
00125 # const double x, const double y, const double z,
00126 # const double rx, const double ry, const double rz, const double rw,
00127 # // bounds x y z
00128 # const double boundx=0.0, const double boundy=0.0, const double boundz=0.0,
00129 # // bounds on rotation x y z
00130 # const double boundrx=0.0, const double boundry=0.0, const double
00131 # boundrz=0.0){


trac_ik_python
Author(s): Sam Pfeiffer
autogenerated on Thu Apr 25 2019 03:39:30