Classes | |
class | CartesianTajectory |
class | ForceTrajectory |
class | JointTrajectory |
Functions | |
def | compute_forces |
compute the force that the arm would apply given the stiffness matrix | |
def | compute_radial_tangential_forces |
return two lists containing the radial and tangential components of the forces. | |
def | compute_workspace |
def | compute_workspace_z |
def | diff_roll_angles |
def | fit_circle |
find the x and y coord of the center of the circle and the radius that best matches the data. | |
def | fit_rotary_joint |
find the x and y coord of the center of the circle of given radius that best matches the data. | |
def | joint_to_cartesian |
def | plot_cartesian |
def | plot_error_forces |
def | plot_forces_quiver |
def | plot_stiff_ellipse_map |
def | plot_stiff_ellipses |
def | plot_stiffness_field |
Variables | |
tuple | actual_cartesian = joint_to_cartesian(d['actual']) |
tuple | angle = math.atan2(y_diff,x_diff) |
list | arm_stiffness_list = d['stiffness'] |
list | asl = [min(scale*s,1.0) for s in arm_stiffness_list] |
tuple | ax = pl.gca() |
string | color = 'k' |
tuple | curr_size = f.get_size_inches() |
tuple | d = ut.load_pickle(fname) |
list | ee_start_pos = pts_list[0] |
tuple | end_angle = tr.angle_within_mod180(math.atan2(end_pt[1,0],end_pt[0,0])-math.radians(90)) |
list | end_pt = pts2d_actual_t[:,-1] |
tuple | eq_cartesian = joint_to_cartesian(d['eq_pt']) |
expt_plot = opt.exptplot | |
tuple | f = pl.gcf() |
list | fig_name = str_parts[0] |
fname = opt.fname | |
tuple | force_mag = ut.norm(forces) |
list | force_traj = d['force'] |
tuple | forces = np.matrix(force_traj.f_list) |
string | help = 'pkl file to use.' |
int | i = 0 |
tuple | leg = pl.legend(loc='best') |
tuple | p = optparse.OptionParser() |
p_list = actual_cartesian.p_list | |
plot_ellipses_flag = opt.plot_ellipses | |
plot_ellipses_vary_flag = opt.pev | |
plot_force_components_flag = opt.pfc | |
plot_force_field_flag = opt.pff | |
plot_forces_error_flag = opt.plot_forces_error | |
plot_forces_flag = opt.plot_forces | |
plot_mechanism_frame = opt.pmf | |
plot_workspace_flag = opt.pwf | |
tuple | pts2d_actual = (np.matrix(actual_cartesian.p_list).T) |
tuple | pts2d_actual_t = rot_mat*(pts2d_actual - translation_mat) |
tuple | pts_2d = (np.matrix(pts_list).T) |
pts_list = actual_cartesian.p_list | |
rad = opt.rad | |
rad_fix = opt.rad_fix | |
float | rad_guess = 0.9 |
list | ratio_list1 = [0.1,0.3,0.5,0.7,0.9] |
list | ratio_list2 = [0.1,0.3,0.5,0.7,0.9] |
list | ratio_list3 = [0.1,0.3,0.5,0.7,0.9] |
tuple | robot_mat = rot_mat*(np.matrix([robot_x_list,robot_y_list]) - translation_mat) |
list | robot_x_list = [-robot_width/2,-robot_width/2,robot_width/2,robot_width/2,-robot_width/2] |
list | robot_y_list = [-robot_length/2,robot_length/2,robot_length/2,-robot_length/2,-robot_length/2] |
tuple | rot_mat = tr.Rz(angle) |
float | s0 = 0.2 |
list | s_list = [s0,s1,s2,s3,0.8] |
list | s_scale = d['stiffness'] |
list | scale = d['stiffness'] |
tuple | show_fig = not(opt.noshow) |
list | sl = [min(s*s_scale,1.0) for s in s_list] |
list | st_pt = pts_2d[:,0] |
tuple | start_angle = tr.angle_within_mod180(math.atan2(st_pt[1,0]-cy,st_pt[0,0]-cx) - math.radians(90)) |
list | start_pt = actual_cartesian.p_list[0] |
tuple | str_parts = fname.split('.') |
int | subplotnum = 234 |
tuple | t0 = time.time() |
tuple | t1 = time.time() |
tuple | t2 = time.time() |
list | time_dict = d['time_dict'] |
list | time_list = d['force'] |
tuple | translation_mat = np.matrix([cx,cy]) |
tuple | x_coord_list = np.matrix(p_list) |
list | x_diff = start_pt[0] |
list | x_guess = ee_start_pos[0] |
xy_flag = opt.xy | |
xyz_flag = opt.xyz | |
xz_flag = opt.xz | |
list | y_diff = start_pt[1] |
list | y_guess = ee_start_pos[1] |
yz_flag = opt.yz |
def arm_trajectories.compute_forces | ( | q_actual_traj, | |
q_eq_traj, | |||
torque_traj, | |||
rel_stiffness_list | |||
) |
compute the force that the arm would apply given the stiffness matrix
q_actual_traj | - Joint Trajectory (actual angles.) |
q_eq_traj | - Joint Trajectory (equilibrium point angles.) |
torque_traj | - JointTrajectory (torques measured at the joints.) |
rel_stiffness_list | - list of 5 elements (stiffness numbers for the joints.) |
Definition at line 162 of file arm_trajectories.py.
def arm_trajectories.compute_radial_tangential_forces | ( | f_list, | |
p_list, | |||
cx, | |||
cy | |||
) |
return two lists containing the radial and tangential components of the forces.
f_list | - list of forces. (each force is a list of 2 or 3 floats) |
p_list | - list of positions. (each position is a list of 2 or 3 floats) |
cx | - x coord of the center of the circle. |
cy | - y coord of the center of the circle. |
Definition at line 218 of file arm_trajectories.py.
def arm_trajectories.compute_workspace | ( | z, | |
plot = False , |
|||
wrist_roll_angle = math.radians(0) , |
|||
subplotnum = None , |
|||
title = '' |
|||
) |
Definition at line 437 of file arm_trajectories.py.
Definition at line 473 of file arm_trajectories.py.
Definition at line 468 of file arm_trajectories.py.
def arm_trajectories.fit_circle | ( | rad_guess, | |
x_guess, | |||
y_guess, | |||
pts, | |||
method, | |||
verbose = True |
|||
) |
find the x and y coord of the center of the circle and the radius that best matches the data.
rad_guess | - guess for the radius of the circle |
x_guess | - guess for x coord of center |
y_guess | - guess for y coord of center. |
pts | - 2xN np matrix of points. |
method | - optimization method. ('fmin' or 'fmin_bfgs') |
verbose | - passed onto the scipy optimize functions. whether to print out the convergence info. |
Definition at line 546 of file arm_trajectories.py.
def arm_trajectories.fit_rotary_joint | ( | rad, | |
x_guess, | |||
y_guess, | |||
pts | |||
) |
find the x and y coord of the center of the circle of given radius that best matches the data.
rad | - radius of the circle (not optimized) |
x_guess | - guess for x coord of center |
y_guess | - guess for y coord of center. |
pts | - 2xN np matrix of points. |
Definition at line 514 of file arm_trajectories.py.
def arm_trajectories.joint_to_cartesian | ( | traj | ) |
traj - JointTrajectory returns CartesianTajectory after performing FK on traj.
Definition at line 75 of file arm_trajectories.py.
def arm_trajectories.plot_cartesian | ( | traj, | |
xaxis = None , |
|||
yaxis = None , |
|||
zaxis = None , |
|||
color = 'b' , |
|||
label = '_nolegend_' , |
|||
linewidth = 2 , |
|||
scatter_size = 20 |
|||
) |
xaxis - x axis for the graph (0,1 or 2) zaxis - for a 3d plot. not implemented.
Definition at line 110 of file arm_trajectories.py.
def arm_trajectories.plot_error_forces | ( | measured_list, | |
calc_list | |||
) |
Definition at line 233 of file arm_trajectories.py.
def arm_trajectories.plot_forces_quiver | ( | pos_traj, | |
force_traj, | |||
color = 'k' |
|||
) |
Definition at line 92 of file arm_trajectories.py.
def arm_trajectories.plot_stiff_ellipse_map | ( | stiffness_list, | |
num | |||
) |
Definition at line 389 of file arm_trajectories.py.
def arm_trajectories.plot_stiff_ellipses | ( | k_cart_list, | |
pos_traj, | |||
skip = 10 , |
|||
subplotnum = 111 |
|||
) |
Definition at line 307 of file arm_trajectories.py.
def arm_trajectories.plot_stiffness_field | ( | k_cart, | |
plottitle = '' |
|||
) |
k_cart,: | 3x3 cartesian space stiffness matrix. |
Definition at line 361 of file arm_trajectories.py.
tuple arm_trajectories::actual_cartesian = joint_to_cartesian(d['actual']) |
Definition at line 691 of file arm_trajectories.py.
tuple arm_trajectories::angle = math.atan2(y_diff,x_diff) |
Definition at line 739 of file arm_trajectories.py.
list arm_trajectories::arm_stiffness_list = d['stiffness'] |
Definition at line 829 of file arm_trajectories.py.
list arm_trajectories::asl = [min(scale*s,1.0) for s in arm_stiffness_list] |
Definition at line 831 of file arm_trajectories.py.
tuple arm_trajectories::ax = pl.gca() |
Definition at line 811 of file arm_trajectories.py.
string arm_trajectories::color = 'k' |
Definition at line 748 of file arm_trajectories.py.
tuple arm_trajectories::curr_size = f.get_size_inches() |
Definition at line 883 of file arm_trajectories.py.
tuple arm_trajectories::d = ut.load_pickle(fname) |
Definition at line 690 of file arm_trajectories.py.
Definition at line 703 of file arm_trajectories.py.
tuple arm_trajectories::end_angle = tr.angle_within_mod180(math.atan2(end_pt[1,0],end_pt[0,0])-math.radians(90)) |
Definition at line 755 of file arm_trajectories.py.
Definition at line 754 of file arm_trajectories.py.
tuple arm_trajectories::eq_cartesian = joint_to_cartesian(d['eq_pt']) |
Definition at line 692 of file arm_trajectories.py.
arm_trajectories::expt_plot = opt.exptplot |
Definition at line 636 of file arm_trajectories.py.
tuple arm_trajectories::f = pl.gcf() |
Definition at line 882 of file arm_trajectories.py.
Definition at line 764 of file arm_trajectories.py.
Definition at line 622 of file arm_trajectories.py.
tuple arm_trajectories::force_mag = ut.norm(forces) |
Definition at line 817 of file arm_trajectories.py.
list arm_trajectories::force_traj = d['force'] |
Definition at line 815 of file arm_trajectories.py.
tuple arm_trajectories::forces = np.matrix(force_traj.f_list) |
Definition at line 816 of file arm_trajectories.py.
string arm_trajectories::help = 'pkl file to use.' |
Definition at line 587 of file arm_trajectories.py.
int arm_trajectories::i = 0 |
Definition at line 648 of file arm_trajectories.py.
tuple arm_trajectories::leg = pl.legend(loc='best') |
Definition at line 808 of file arm_trajectories.py.
tuple arm_trajectories::p = optparse.OptionParser() |
Definition at line 585 of file arm_trajectories.py.
Definition at line 853 of file arm_trajectories.py.
arm_trajectories::plot_ellipses_flag = opt.plot_ellipses |
Definition at line 627 of file arm_trajectories.py.
Definition at line 635 of file arm_trajectories.py.
Definition at line 629 of file arm_trajectories.py.
arm_trajectories::plot_force_field_flag = opt.pff |
Definition at line 630 of file arm_trajectories.py.
arm_trajectories::plot_forces_error_flag = opt.plot_forces_error |
Definition at line 628 of file arm_trajectories.py.
Definition at line 626 of file arm_trajectories.py.
arm_trajectories::plot_mechanism_frame = opt.pmf |
Definition at line 631 of file arm_trajectories.py.
arm_trajectories::plot_workspace_flag = opt.pwf |
Definition at line 638 of file arm_trajectories.py.
tuple arm_trajectories::pts2d_actual = (np.matrix(actual_cartesian.p_list).T) |
Definition at line 750 of file arm_trajectories.py.
Definition at line 751 of file arm_trajectories.py.
tuple arm_trajectories::pts_2d = (np.matrix(pts_list).T) |
Definition at line 707 of file arm_trajectories.py.
Definition at line 702 of file arm_trajectories.py.
Definition at line 633 of file arm_trajectories.py.
arm_trajectories::rad_fix = opt.rad_fix |
Definition at line 637 of file arm_trajectories.py.
Definition at line 711 of file arm_trajectories.py.
list arm_trajectories::ratio_list1 = [0.1,0.3,0.5,0.7,0.9] |
Definition at line 649 of file arm_trajectories.py.
list arm_trajectories::ratio_list2 = [0.1,0.3,0.5,0.7,0.9] |
Definition at line 650 of file arm_trajectories.py.
list arm_trajectories::ratio_list3 = [0.1,0.3,0.5,0.7,0.9] |
Definition at line 651 of file arm_trajectories.py.
tuple arm_trajectories::robot_mat = rot_mat*(np.matrix([robot_x_list,robot_y_list]) - translation_mat) |
Definition at line 746 of file arm_trajectories.py.
list arm_trajectories::robot_x_list = [-robot_width/2,-robot_width/2,robot_width/2,robot_width/2,-robot_width/2] |
Definition at line 744 of file arm_trajectories.py.
list arm_trajectories::robot_y_list = [-robot_length/2,robot_length/2,robot_length/2,-robot_length/2,-robot_length/2] |
Definition at line 745 of file arm_trajectories.py.
tuple arm_trajectories::rot_mat = tr.Rz(angle) |
Definition at line 740 of file arm_trajectories.py.
float arm_trajectories::s0 = 0.2 |
Definition at line 661 of file arm_trajectories.py.
list arm_trajectories::s_list = [s0,s1,s2,s3,0.8] |
Definition at line 667 of file arm_trajectories.py.
list arm_trajectories::s_scale = d['stiffness'] |
Definition at line 777 of file arm_trajectories.py.
list arm_trajectories::scale = d['stiffness'] |
Definition at line 830 of file arm_trajectories.py.
arm_trajectories::show_fig = not(opt.noshow) |
Definition at line 634 of file arm_trajectories.py.
Definition at line 778 of file arm_trajectories.py.
list arm_trajectories::st_pt = pts_2d[:,0] |
Definition at line 791 of file arm_trajectories.py.
tuple arm_trajectories::start_angle = tr.angle_within_mod180(math.atan2(st_pt[1,0]-cy,st_pt[0,0]-cx) - math.radians(90)) |
Definition at line 792 of file arm_trajectories.py.
Definition at line 736 of file arm_trajectories.py.
tuple arm_trajectories::str_parts = fname.split('.') |
Definition at line 763 of file arm_trajectories.py.
int arm_trajectories::subplotnum = 234 |
Definition at line 842 of file arm_trajectories.py.
tuple arm_trajectories::t0 = time.time() |
Definition at line 708 of file arm_trajectories.py.
tuple arm_trajectories::t1 = time.time() |
Definition at line 715 of file arm_trajectories.py.
tuple arm_trajectories::t2 = time.time() |
Definition at line 717 of file arm_trajectories.py.
Definition at line 781 of file arm_trajectories.py.
list arm_trajectories::time_list = d['force'] |
Definition at line 860 of file arm_trajectories.py.
tuple arm_trajectories::translation_mat = np.matrix([cx,cy]) |
Definition at line 741 of file arm_trajectories.py.
tuple arm_trajectories::x_coord_list = np.matrix(p_list) |
Definition at line 862 of file arm_trajectories.py.
Definition at line 737 of file arm_trajectories.py.
Definition at line 704 of file arm_trajectories.py.
Definition at line 623 of file arm_trajectories.py.
arm_trajectories::xyz_flag = opt.xyz |
Definition at line 632 of file arm_trajectories.py.
arm_trajectories::xz_flag = opt.xz |
Definition at line 625 of file arm_trajectories.py.
Definition at line 738 of file arm_trajectories.py.
Definition at line 705 of file arm_trajectories.py.
arm_trajectories::yz_flag = opt.yz |
Definition at line 624 of file arm_trajectories.py.