Functions | Variables
2010_icra_epc_pull::segway_motion_calc Namespace Reference

Functions

def cartesian_to_polar
def close_to_boundary
def compute_boundary
 compute the boundary of the 2D points.
def dist_from_boundary
 return distance from boundary.
def optimize_position
def point_contained
 mx,my,ma - motion of the robot cx,cy - axis of mechanism in robot frame.
def polar_to_cartesian
def pts_within_dist
def segway_motion_repulse
 apologies for the poor name.
def tlRts
 rotate vector from torso local to torso start frame.
def tlTts
 transform from torso start to torso local frame.
def tsRtl
 rotate vector from torso local to torso start frame.
def tsTtl
 transform from torso local to torso start frame.
def vec_from_boundary
 return 2x1 vector from closest boundary point
def visualize_boundary

Variables

tuple bpts = compute_boundary(pts)
tuple d = ut.load_pickle('../../pkls/workspace_dict_2009Sep05_200116.pkl')
tuple k = d.keys()
tuple k_idx = np.argmin(np.abs(np.array(k)-z))
list pts = d[k[k_idx]]
float rad = 0.4
float z = 0.23

Function Documentation

def 2010_icra_epc_pull.segway_motion_calc.cartesian_to_polar (   pts)
Parameters:
pts- 2xN np matrix
Returns:
r,theta (two 1D np arrays)

Definition at line 50 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.close_to_boundary (   curr_pos,
  bndry,
  pts,
  dist_thresh 
)
Parameters:
curr_pos- current location of end effector. 3x1 np matrix
bndry- workspace boundary. 2xN np matrix

Definition at line 226 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.compute_boundary (   pts)

compute the boundary of the 2D points.

Making assumptions about the density of the points, tested with workspace_dict only.

Parameters:
pts- 2xN np matrix

Definition at line 174 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.dist_from_boundary (   curr_pos,
  bndry,
  pts 
)

return distance from boundary.

(-ve if outside the boundary)

Parameters:
curr_pos- can be 3x1 np matrix
bndry- boundary (2xN np matrix)
pts- 2xN np matrix. pts whose boundary is bndry

Definition at line 203 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.optimize_position (   cx,
  cy,
  rad,
  curr_pos,
  eq_pos,
  pts,
  bndry,
  start_angle,
  end_angle,
  buffer,
  tangential_force 
)

Definition at line 86 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.point_contained (   mx,
  my,
  ma,
  cx,
  cy,
  rad,
  pts,
  start_angle,
  end_angle,
  buffer 
)

mx,my,ma - motion of the robot cx,cy - axis of mechanism in robot frame.

start_angle,end_angle - between 0 and 2*pi

Definition at line 68 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.polar_to_cartesian (   r,
  theta 
)
Parameters:
r- 1D np array
theta- 1D np array (RADIANS)
Returns:
2xN np matrix of cartesian points

Definition at line 59 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.pts_within_dist (   p,
  pts,
  min_dist,
  max_dist 
)

Definition at line 294 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.segway_motion_repulse (   curr_pos_tl,
  eq_pt_tl,
  bndry,
  all_pts 
)

apologies for the poor name.

computes the translation of the torso frame that move the eq pt away from closest boundary and rotate such that local x axis is perp to mechanism returns 2x1 np matrix, angle

Definition at line 305 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.tlRts (   vecs_ts,
  a 
)

rotate vector from torso local to torso start frame.

Parameters:
vecs_tl- 3xN np matrix in tl coord frame.
a- motion of the segway (in the ms frame)
Returns:
vecs_ts

Definition at line 287 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.tlTts (   pts_ts,
  x,
  y,
  a 
)

transform from torso start to torso local frame.

Parameters:
pts- 3xN np matrix in ts coord frame.
x,y,a- motion of the segway (in the ms frame)
Returns:
pts_tl

Definition at line 255 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.tsRtl (   vecs_tl,
  a 
)

rotate vector from torso local to torso start frame.

Parameters:
vecs_tl- 3xN np matrix in tl coord frame.
a- motion of the segway (in the ms frame)
Returns:
vecs_ts

Definition at line 277 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.tsTtl (   pts_tl,
  x,
  y,
  a 
)

transform from torso local to torso start frame.

Parameters:
pts- 3xN np matrix in tl coord frame.
x,y,a- motion of the segway (in the ms frame)
Returns:
pts_ts

Definition at line 266 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.vec_from_boundary (   curr_pos,
  bndry 
)

return 2x1 vector from closest boundary point

Definition at line 192 of file segway_motion_calc.py.

def 2010_icra_epc_pull.segway_motion_calc.visualize_boundary ( )

Definition at line 230 of file segway_motion_calc.py.


Variable Documentation

tuple 2010_icra_epc_pull::segway_motion_calc::bpts = compute_boundary(pts)

Definition at line 358 of file segway_motion_calc.py.

tuple 2010_icra_epc_pull::segway_motion_calc::d = ut.load_pickle('../../pkls/workspace_dict_2009Sep05_200116.pkl')

Definition at line 349 of file segway_motion_calc.py.

tuple 2010_icra_epc_pull::segway_motion_calc::k = d.keys()

Definition at line 351 of file segway_motion_calc.py.

tuple 2010_icra_epc_pull::segway_motion_calc::k_idx = np.argmin(np.abs(np.array(k)-z))

Definition at line 352 of file segway_motion_calc.py.

list 2010_icra_epc_pull::segway_motion_calc::pts = d[k[k_idx]]

Definition at line 353 of file segway_motion_calc.py.

float 2010_icra_epc_pull::segway_motion_calc::rad = 0.4

Definition at line 360 of file segway_motion_calc.py.

float 2010_icra_epc_pull::segway_motion_calc::z = 0.23

Definition at line 350 of file segway_motion_calc.py.



2010_icra_epc_pull
Author(s): Advait Jain, Charles C. Kemp (Healthcare Robotics Lab, Georgia Tech)
autogenerated on Wed Nov 27 2013 12:14:43