Classes | Functions | Variables
doors_forces_kinematics::arm_trajectories Namespace Reference

Classes

class  CartesianTajectory
class  ForceTrajectory
class  JointTrajectory
class  PlanarTrajectory
 class to store trajectory of a coord frame executing planar motion (x,y,a) data only - use for pickling More...

Functions

def account_segway_motion
 changes the cartesian trajectory to put everything in the same frame.
def account_zenithering
def compute_radial_tangential_forces
 return two lists containing the radial and tangential components of the forces.
def filter_cartesian_trajectory
 remove the initial part of the trjectory in which the hook is not moving.
def filter_trajectory_force
 remove the last part of the trjectory in which the hook might have slipped off
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_circle_priors
def joint_to_cartesian
def plot_cartesian
def plot_forces_quiver

Variables

tuple actual_cartesian
tuple actual_cartesian_tl = joint_to_cartesian(d['actual'], d['arm'])
string addon = ''
float alpha = 0.7
string axis = 'equal'
tuple c_ts = np.matrix([cx, cy, 0.])
tuple cep_2d = np.matrix(cep_force_clean.p_list)
list cep_2d_s = cep_2d[:,::subsample_ratio]
list cep_2d_zoom = cep_2d[:,:zoom_location]
list cep_text = cep_2d_zoom[:,-1]
 color = wrist_color)
tuple curr_size = f.get_size_inches()
list current_pos = pts_2d_zoom[:,-1]
tuple d = ut.load_pickle(fname)
string dest = 'icra_presentation_plot'
list ee_start_pos = pts_list[0]
tuple end_angle
list end_pt = pts_2d[:,-1]
tuple eq_cartesian = account_zenithering(eq_cartesian, d['zenither_list'])
tuple eq_cartesian_tl = joint_to_cartesian(d['eq_pt'], d['arm'])
 eq_pts_list = eq_cartesian.p_list
 expt_plot = opt.exptplot
tuple f = pl.gcf()
string fig_name = 'epc'
int fig_number = 1
 fname = opt.fname
int fontsize = 25
list force_list = d['force']
tuple frad = (wrist_force[0:2,:].T * radial_vec)
tuple frad_text = rad_text_loc+np.matrix([0.,0.015])
string help = 'pkl file to use.'
tuple hook_force_motion = -(frad - 5)
list hw_text = cep_2d_zoom[:,-1]
int i = 0
string interval = 'r'
string label = 'Actual\_opt'
float marker_edge_width = 1.5
string method = 'fmin_bfgs'
list mw_text = cep_2d_zoom[:,-1]
list new_cep = cep_2d_zoom[:,-1]
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
list pts_2d_s = pts_2d[:,::subsample_ratio]
list pts_2d_zoom = pts_2d[:,:zoom_location]
 pts_list = actual_cartesian.p_list
 rad = opt.rad
 rad_guess = rad
list rad_text_loc = pts_2d_zoom[:,-1]
tuple radial_vec = current_pos-np.matrix([cx,cy])
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]
string s = '$h[t]$'
float s0 = 0.2
list s_list = [s0,s1,s2,s3,0.8]
int scatter_size = 7
tuple show_fig = not(opt.noshow)
list st_pt = pts_2d[:,0]
tuple start_angle
tuple str_parts = fname.split('.')
tuple sturm_file = open(sturm_file_name,'w')
list sturm_file_name = str_parts[0]
 sturm_output = opt.sturm
 sturm_pts = cartesian_force_clean.p_list
int subplotnum = 234
int subsample_ratio = 1
list tan_text_loc = pts_2d_zoom[:,-1]
float tangential_motion = 0.01
tuple tangential_vec = np.matrix([[0,-1],[1,0]])
list time_list = d['force']
 total_cep_motion = hook_force_motion+tangential_motion
tuple wf_text = rad_text_loc+np.matrix([-0.06,0.015])
string wrist_color = '#A0A000'
tuple wrist_force = -np.matrix(force_new.f_list[zoom_location])
tuple x_coord_list = np.matrix(p_list)
list x_guess = ee_start_pos[0]
 xy_flag = opt.xy
 xyz_flag = opt.xyz
 xz_flag = opt.xz
list y_guess = ee_start_pos[1]
 yz_flag = opt.yz
int zoom_location = 10

Function Documentation

def doors_forces_kinematics.arm_trajectories.account_segway_motion (   cart_traj,
  force_traj,
  st 
)

changes the cartesian trajectory to put everything in the same frame.

NOTE - velocity transformation does not work if the segway is also moving. This is because I am not logging the velocity of the segway.

Parameters:
pts- CartesianTajectory
st- object of type PlanarTrajectory (segway trajectory)
Returns:
CartesianTajectory

Definition at line 292 of file arm_trajectories.py.

Definition at line 323 of file arm_trajectories.py.

return two lists containing the radial and tangential components of the forces.

Parameters:
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.
Returns:
list of magnitude of radial component, list of magnitude tangential component, list of the force along the remaining direction

Definition at line 168 of file arm_trajectories.py.

remove the initial part of the trjectory in which the hook is not moving.

Parameters:
ct- cartesian trajectory of the end effector in the world frame.
Returns:
2xN np matrix, reject_idx

Definition at line 345 of file arm_trajectories.py.

remove the last part of the trjectory in which the hook might have slipped off

Parameters:
ct- cartesian trajectory of the end effector in the world frame.
ft- force trajectory
Returns:
cartesian trajectory with the zero force end part removed, force trajectory

Definition at line 368 of file arm_trajectories.py.

def doors_forces_kinematics.arm_trajectories.fit_circle (   rad_guess,
  x_guess,
  y_guess,
  pts,
  method,
  verbose = True,
  rad_fix = False 
)

find the x and y coord of the center of the circle and the radius that best matches the data.

Parameters:
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.
Returns:
r,x,y (radius, x and y coord of the center of the circle)

Definition at line 233 of file arm_trajectories.py.

def doors_forces_kinematics.arm_trajectories.fit_circle_priors (   rad_guess,
  x_guess,
  y_guess,
  pts,
  sigma_r,
  sigma_xy,
  sigma_pts,
  verbose = True 
)

Definition at line 191 of file arm_trajectories.py.

Parameters:
traj- JointTrajectory
Returns:
CartesianTajectory after performing FK on traj to compute cartesian position, velocity

Definition at line 67 of file arm_trajectories.py.

def doors_forces_kinematics.arm_trajectories.plot_cartesian (   traj,
  xaxis = None,
  yaxis = None,
  zaxis = None,
  color = 'b',
  label = '_nolegend_',
  linewidth = 2,
  scatter_size = 10,
  plot_velocity = False 
)
Parameters:
xaxis- x axis for the graph (0,1 or 2)
zaxis- for a 3d plot. not implemented.

Definition at line 111 of file arm_trajectories.py.

def doors_forces_kinematics.arm_trajectories.plot_forces_quiver (   pos_traj,
  force_traj,
  color = 'k' 
)

Definition at line 90 of file arm_trajectories.py.


Variable Documentation

Initial value:
00001 account_zenithering(actual_cartesian,
00002                                                d['zenither_list'])

Definition at line 509 of file arm_trajectories.py.

Definition at line 506 of file arm_trajectories.py.

Definition at line 843 of file arm_trajectories.py.

Definition at line 600 of file arm_trajectories.py.

Definition at line 755 of file arm_trajectories.py.

tuple doors_forces_kinematics::arm_trajectories::c_ts = np.matrix([cx, cy, 0.])

Definition at line 553 of file arm_trajectories.py.

tuple doors_forces_kinematics::arm_trajectories::cep_2d = np.matrix(cep_force_clean.p_list)

Definition at line 583 of file arm_trajectories.py.

Definition at line 592 of file arm_trajectories.py.

Definition at line 614 of file arm_trajectories.py.

Definition at line 744 of file arm_trajectories.py.

Definition at line 693 of file arm_trajectories.py.

Definition at line 854 of file arm_trajectories.py.

Definition at line 666 of file arm_trajectories.py.

Definition at line 505 of file arm_trajectories.py.

string doors_forces_kinematics::arm_trajectories::dest = 'icra_presentation_plot'

Definition at line 440 of file arm_trajectories.py.

Definition at line 527 of file arm_trajectories.py.

Initial value:
00001 tr.angle_within_mod180(math.atan2(pts_2d[1,-1]-cy,
00002                                pts_2d[0,-1]-cx) - math.pi/2)

Definition at line 556 of file arm_trajectories.py.

Definition at line 768 of file arm_trajectories.py.

Definition at line 515 of file arm_trajectories.py.

Definition at line 512 of file arm_trajectories.py.

Definition at line 526 of file arm_trajectories.py.

Definition at line 457 of file arm_trajectories.py.

Definition at line 853 of file arm_trajectories.py.

Definition at line 605 of file arm_trajectories.py.

Definition at line 606 of file arm_trajectories.py.

Definition at line 444 of file arm_trajectories.py.

Definition at line 697 of file arm_trajectories.py.

Definition at line 531 of file arm_trajectories.py.

Definition at line 689 of file arm_trajectories.py.

Definition at line 703 of file arm_trajectories.py.

Definition at line 410 of file arm_trajectories.py.

Definition at line 713 of file arm_trajectories.py.

Definition at line 720 of file arm_trajectories.py.

Definition at line 463 of file arm_trajectories.py.

Definition at line 602 of file arm_trajectories.py.

Definition at line 559 of file arm_trajectories.py.

Definition at line 590 of file arm_trajectories.py.

Definition at line 551 of file arm_trajectories.py.

Definition at line 732 of file arm_trajectories.py.

Definition at line 753 of file arm_trajectories.py.

tuple doors_forces_kinematics::arm_trajectories::p = optparse.OptionParser()

Definition at line 408 of file arm_trajectories.py.

Definition at line 810 of file arm_trajectories.py.

Definition at line 449 of file arm_trajectories.py.

Definition at line 456 of file arm_trajectories.py.

Definition at line 451 of file arm_trajectories.py.

Definition at line 452 of file arm_trajectories.py.

Definition at line 450 of file arm_trajectories.py.

Definition at line 448 of file arm_trajectories.py.

Definition at line 579 of file arm_trajectories.py.

Definition at line 613 of file arm_trajectories.py.

Definition at line 525 of file arm_trajectories.py.

Definition at line 454 of file arm_trajectories.py.

Definition at line 549 of file arm_trajectories.py.

Definition at line 673 of file arm_trajectories.py.

Definition at line 667 of file arm_trajectories.py.

Definition at line 464 of file arm_trajectories.py.

Definition at line 465 of file arm_trajectories.py.

Definition at line 466 of file arm_trajectories.py.

Definition at line 722 of file arm_trajectories.py.

Definition at line 476 of file arm_trajectories.py.

Definition at line 482 of file arm_trajectories.py.

Definition at line 589 of file arm_trajectories.py.

Definition at line 455 of file arm_trajectories.py.

Definition at line 767 of file arm_trajectories.py.

Initial value:
00001 tr.angle_within_mod180(math.atan2(pts_2d[1,0]-cy,
00002                                pts_2d[0,0]-cx) - math.pi/2)

Definition at line 554 of file arm_trajectories.py.

Definition at line 534 of file arm_trajectories.py.

Definition at line 537 of file arm_trajectories.py.

Definition at line 535 of file arm_trajectories.py.

Definition at line 458 of file arm_trajectories.py.

Definition at line 538 of file arm_trajectories.py.

Definition at line 799 of file arm_trajectories.py.

Definition at line 578 of file arm_trajectories.py.

Definition at line 679 of file arm_trajectories.py.

Definition at line 714 of file arm_trajectories.py.

Definition at line 669 of file arm_trajectories.py.

Definition at line 820 of file arm_trajectories.py.

Definition at line 715 of file arm_trajectories.py.

Definition at line 695 of file arm_trajectories.py.

Definition at line 687 of file arm_trajectories.py.

Definition at line 688 of file arm_trajectories.py.

Definition at line 822 of file arm_trajectories.py.

Definition at line 528 of file arm_trajectories.py.

Definition at line 445 of file arm_trajectories.py.

Definition at line 453 of file arm_trajectories.py.

Definition at line 447 of file arm_trajectories.py.

Definition at line 529 of file arm_trajectories.py.

Definition at line 446 of file arm_trajectories.py.

Definition at line 612 of file arm_trajectories.py.



doors_forces_kinematics
Author(s): Advait Jain. Advisor: Prof. Charlie Kemp (Healthcare Robotics Lab)
autogenerated on Wed Nov 27 2013 11:41:11