multi_link_six_planar.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import numpy as np
00003 import math
00004 from multi_link_common import *
00005 
00006 #height is probably 0 from multi_link_common.py
00007 #total mass and total length are also defined in multi_link_common.py
00008 
00009 num_links = 6.0
00010 link_length = total_length/num_links
00011 link_mass = total_mass/num_links
00012 
00013 ee_location = np.matrix([0., -link_length*6.0, height]).T
00014 #bod_shapes = ['cube', 'cube', 'cube', 'cube', 'cube', 'cube']  
00015 bod_shapes = ['capsule', 'capsule', 'capsule', 'capsule', 'capsule', 'capsule'] 
00016 
00017 bod_dimensions = [[0.03, 0.03, link_length]]*6
00018 
00019 bod_com_position = [[0., -link_length/2., height], 
00020                     [0., -3.0/2.0*link_length, height], 
00021                     [0., -5.0/2.0*link_length, height],
00022                     [0., -7.0/2.0*link_length, height], 
00023                     [0., -9.0/2.0*link_length, height], 
00024                     [0., -11.0/2.0*link_length, height]]
00025 
00026 
00027 bod_color = [[0.4, 0.4, 0.4, 1], [0.8, 0.8, 0.8, 1], [0.33, 0.33, 0.33, 1], [0.5, 0.5, 0.5, 1], [0.1, 0.1, 0.1, 1], [0.7, 0.7, 0.7, 1]]
00028 bod_num_links = 6
00029 bod_mass = [link_mass]*bod_num_links
00030 
00031 bod_names = ['link1', 'link2', 'link3', 'link4', 'link5', 'link6']
00032 bodies ={'shapes':bod_shapes, 'dim':bod_dimensions, 'num_links':bod_num_links,
00033          'com_pos':bod_com_position, 'mass':bod_mass, 'name':bod_names, 'color':bod_color}
00034 
00035 b_jt_axis = [[0.,0.,1.],[0.,0.,1.], [0.,0.,1.], [0.,0.,1.],[0.,0.,1.], [0.,0.,1.]]
00036 b_jt_anchor = [[0., 0., height], 
00037                [0., -link_length, height], 
00038                [0., -2*link_length, height],
00039                [0., -3*link_length, height],
00040                [0., -4*link_length, height],
00041                [0., -5*link_length, height]]
00042 
00043 
00044 b_jt_kp = [24., 15., 9., 7., 3.2, 1.8]
00045 b_jt_kd = [6.0, 4.5, 2.5, 1.8, 1.0, 0.6]
00046 b_jt_limits_max = np.radians([180, 120, 120, 120, 120, 120]).tolist()
00047 b_jt_limits_min = np.radians([-180, -120, -120, -120, -120, -120]).tolist()
00048 b_jt_axis = [[0.,0.,1.],[0.,0.,1.], [0.,0.,1.], [0.,0.,1.],[0.,0.,1.], [0.,0.,1.]]
00049 b_jt_attach = [[0, -1], [1, 0], [2,1], [3,2], [4,3], [5,4], [6,5]]
00050 b_jt_start = [-1.75, 0.517, 0.814, 1.10, 1.01, 0.659] #(gives ee pos of [0, -0.2, 0]
00051 
00052 b_jts = {'anchor':b_jt_anchor, 'axis':b_jt_axis, 'jt_lim_max':b_jt_limits_max,
00053          'jt_lim_min':b_jt_limits_min, 'jt_init':b_jt_start, 'jt_attach':b_jt_attach,
00054          'jt_stiffness':b_jt_kp, 'jt_damping':b_jt_kd}
00055 
00056 
00057 
00058 
00059 


hrl_common_code_darpa_m3
Author(s): Advait Jain, Marc Killpack. Advisor: Prof. Charlie Kemp. Healthcare Robotics Lab, Georgia Tech
autogenerated on Wed Nov 27 2013 11:34:42