00001
00002 import numpy as np
00003 import math
00004 from multi_link_common import *
00005
00006
00007
00008
00009 num_links = 3.0
00010 link_length = total_length/num_links
00011 link_mass = total_mass/num_links
00012
00013 ee_location = np.matrix([0., -total_length, height]).T
00014
00015 bod_shapes = ['capsule', 'capsule', 'capsule', 'capsule']
00016
00017 bod_dimensions = [[0.03, 0.03, link_length]]*3
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
00023
00024 bod_color = [[0.4, 0.4, 0.4, 1], [0.8, 0.8, 0.8, 1], [0.33, 0.33, 0.33, 1]]
00025 bod_num_links = 3
00026 bod_mass = [link_mass]*bod_num_links
00027
00028 bod_names = ['link1', 'link2', 'link3']
00029 bodies ={'shapes':bod_shapes, 'dim':bod_dimensions, 'num_links':bod_num_links,
00030 'com_pos':bod_com_position, 'mass':bod_mass, 'name':bod_names, 'color':bod_color}
00031
00032 b_jt_axis = [[0.,0.,1.],[0.,0.,1.], [0.,0.,1.]]
00033 b_jt_anchor = [[0., 0., height],
00034 [0., -link_length, height],
00035 [0., -2*link_length, height]]
00036
00037 b_jt_kp = [30., 20., 15.]
00038 b_jt_kd = [15., 10., 8.]
00039 b_jt_limits_max = np.radians([180, 120, 120]).tolist()
00040 b_jt_limits_min = np.radians([-180, -120, -120]).tolist()
00041 b_jt_axis = [[0.,0.,1.],[0.,0.,1.], [0.,0.,1.]]
00042 b_jt_attach = [[0, -1], [1, 0], [2,1]]
00043
00044 b_jt_start = [-1.74, 1.78, 1.86]
00045
00046
00047 b_jts = {'anchor':b_jt_anchor, 'axis':b_jt_axis, 'jt_lim_max':b_jt_limits_max,
00048 'jt_lim_min':b_jt_limits_min, 'jt_init':b_jt_start, 'jt_attach':b_jt_attach,
00049 'jt_stiffness':b_jt_kp, 'jt_damping':b_jt_kd}
00050
00051