def make_whisker(dim, q0, L, rbase=100e-6, taper=1.0/15, damping_ratio=None, rho=1.0, E=3.3e9): """ Assembles the whisker based on material properties and initial configuration. The default material and geometric properties from elastica2d are used by default. """ assert dim in [2,3], "dimension must be 2 or 3" print 19*'-'+'BUILD WHISKER (%dd)'%dim+19*'-' print 'Getting parameters...', if dim==2: N = len(q0)-2 else: N = (len(q0)-4)/2 I = calc_inertia(N, rbase, taper) K = E*I/L M = calc_mass(L, N, rho, rbase, taper) if damping_ratio<0: damping_ratio = np.append([1.0], get_interp_damping(L,N)) C = calc_damping(N, K, M, L, damping_ratio) parameters = {'L': L, 'k': K[:-1], 'c': C, 'm': M, 'N':N} print 'done' print 'Building system...', if dim==2: whisker = Whisker2D(parameters) whisker.reference_shape = q0 peg_frames = [ty('py', kinematic=True), [tz('pz', kinematic=True, name='peg_frame')]] else: whisker = Whisker3D(parameters, q0) peg_frames = [tx('px', kinematic=True), [ty('py', kinematic=True), [tz('pz', kinematic=True, name='peg_frame')]]] whisker.world_frame.import_frames(peg_frames) print 'done' return whisker
def whisker_frames(self, curvature, base_pos, base_rot): """ Creates a list of frames that define the whisker. """ if curvature is None: ref_angles = np.zeros(self.num_links) else: ref_angles = get_angles_from_curvature(self.lengths, curvature) frames = [] for j in reversed(range(1, self.num_links)): frames = [tx(self.lengths[j], name='Link-%d' %j), frames] frames = [rz('theta-%d_z' %j), frames] frames = [ry('theta-%d_y' %j), frames] #frames = [rx('theta-%d_x' %j), frames] frames = [rz(-ref_angles[j]), frames] frames = [tx(self.lengths[0], name='Link-0'), frames] frames = [rz('theta-0_z', name='Moving Base Point'), frames] frames = [ry('theta-0_y'), frames] frames = [rx('theta-0_x'), frames] frames = [tz('z'), [ty('y'), [tx('x'), frames]]] (X, Y, Z) = base_pos (theta, phi, zeta) = base_rot # Rotate to the correct position. frames = [rz(theta), [ry(phi), [rx(zeta), frames]]] # Place the whisker at the correct spot on the mystacial pad and add an angle # that drives the whisking motion. frames = [tx(X), [ty(Y),[ tz(Z, name='Base Point'), [rz('Driving Angle', name="Driving Angle"), frames]]]] frames = [ rz(0.0, name='Head'), frames] return frames
def point_mass_frames(self, num_links, masses): frames = [tx('x_base'), [ty('y_base'), [tz('z_base', name='Base Point')]] ] for j in range(num_links): frames += [tx('x-%d' %j), [ty('y-%d' %j), [tz('z-%d' %j, mass=masses[j], name='Link-%d' %j)]] ] frames += [rz(0.0, name='Head')] return frames
def make_skeleton(dimensions={}, joints={}): dim = fill_dimensions(dimensions) joints = fill_joints(joints) frames = [ tx(joints['torso_tx']), [ty(joints['torso_ty']), [tz(joints['torso_tz']), [ rz(joints['torso_rz']), [ ry(joints['torso_ry']), [ rx(joints['torso_rx'], name='pelvis', mass=dim['pelvis_mass']), [ tx(-dim['lhip_width'], name='lhip'), [ rz(joints['lhip_rz']), [ry(joints['lhip_ry']), [rx(joints['lhip_rx'], name='lfemur'), [ tz(-dim['lfemur_length']/2, name='lfemur_mass', mass=dim['femur_mass']), tz(-dim['lfemur_length'], name='lfemur_end'), [ rx(joints['lknee_rx'], name='ltibia'), [ tz(-dim['ltibia_length']/2, name='ltibia_mass', mass=dim['tibia_mass']), tz(-dim['ltibia_length'], name='ltibia_end'), [ rz(joints['lfoot_rz']), [ry(joints['lfoot_ry']), [ rx(joints['lfoot_rx'], name='lfoot'), [ ty(dim['lfoot_length'], name='lfoot_end')]]]]]]]]]], tx(dim['rhip_width'], name='rhip'), [ rz(joints['rhip_rz']), [ry(joints['rhip_ry']), [rx(joints['rhip_rx'], name='rfemur'), [ tz(-dim['rfemur_length']/2, name='rfemur_mass', mass=dim['femur_mass']), tz(-dim['rfemur_length'], name='rfemur_end'), [ rx(joints['rknee_rx'], name='rtibia'), [ tz(-dim['rtibia_length']/2, name='rtibia_mass', mass=dim['tibia_mass']), tz(-dim['rtibia_length'], name='rtibia_end'), [ rz(joints['rfoot_rz']), [ry(joints['rfoot_ry']), [ rx(joints['rfoot_rx'], name='rfoot'), [ ty(dim['rfoot_length'], name='rfoot_end')]]]]]]]]]], tz(dim['upper_torso_length'], name='spine_top'), [ tz(dim['neck_length'], name='neck'), [ rz(joints['neck_rz']), [ry(joints['neck_ry']), [ rx(joints['neck_rz'], name='neck_joint'), [ tz(dim['lower_head_length'], name='head'), [ tz(dim['upper_head_length'], name='head_center', mass=dim['head_mass']), [ tz(dim['final_head_length'], name='head_end')]]]]]], tx(-dim['lshoulder_width'], name='lshoulder'), [ rz(joints['lshoulder_rz']), [ry(joints['lshoulder_ry']), [ rx(joints['lshoulder_rx'], name='lhumerus'), [ tz(-dim['lhumerus_length']/2, name='lhumerus_mass', mass=dim['humerus_mass']), tz(-dim['lhumerus_length'], name='lhumerus_end'), [ rx(joints['lelbow_rx'], name='lradius'), [ tz(-dim['lradius_length']/2, name='lradius_mass', mass=dim['radius_mass']), tz(-dim['lradius_length'], name='lradius_end'), [ rz(joints['lhand_rz']), [ry(joints['lhand_ry']), [ rx(joints['lhand_rx'], name='lhand'), [ tz(-dim['lhand_length'], name='lhand_end')]]]]]]]]]], tx(dim['rshoulder_width'], name='rshoulder'), [ rz(joints['rshoulder_rz']), [ry(joints['rshoulder_ry']), [ rx(joints['rshoulder_rx'], name='rhumerus'), [ tz(-dim['rhumerus_length']/2, name='rhumerus_mass', mass=dim['humerus_mass']), tz(-dim['rhumerus_length'], name='rhumerus_end'), [ rx(joints['relbow_rx'], name='rradius'), [ tz(-dim['rradius_length']/2, name='rradius_mass', mass=dim['radius_mass']), tz(-dim['rradius_length'], name='rradius_end'), [ rz(joints['rhand_rz']), [ry(joints['rhand_ry']), [ rx(joints['rhand_rx'], name='rhand'), [ tz(-dim['rhand_length'], name='rhand_end')]]]]]]]]]] ]]]]]]]] return frames
def whisker_frames(self, L): """Creates a list of frames that define the whisker.""" frames = [] for j in reversed(range(1, self.num_links)): frames = [ty(L, name='Link-%d' %j), frames] frames = [rx('theta-%d' %j, name='f%d' %j), frames] frames = [rx('curvature-%d' %j, kinematic=True), frames] frames = [ty(L, name='Link-0'), frames] frames = [tz('z'), [ty('y', name='Base_Point'), frames]] frames = [rx('theta-0', name='f0'), frames] frames = [tz('z0', kinematic=True), [ty('y0', kinematic=True), frames]] frames = [rx('curvature-0', kinematic=True), frames] return frames
def point_mass_frames(self, num_links, masses): frames = [ tx('x_base'), [ty('y_base'), [tz('z_base', name='Base Point')]] ] for j in range(num_links): frames += [ tx('x-%d' % j), [ ty('y-%d' % j), [tz('z-%d' % j, mass=masses[j], name='Link-%d' % j)] ] ] frames += [rz(0.0, name='Head')] return frames
def MassSystem2D(): # define system: system = trep.System() frames = [ tx('xm', name='x-mass'), [ty('ym', name='y-mass', mass=BALL_MASS)], ty(1, name='robot_plane'), [tx('xr', name='x-robot', kinematic=True)] ] system.import_frames(frames) trep.potentials.Gravity(system, (0, -g, 0)) trep.forces.Damping(system, 0.05) # add string constraint as a kinematic configuration var trep.constraints.Distance(system, 'y-mass', 'x-robot', 'r') return system
def MassSystem2D(): # define system: system = trep.System() frames = [ tx('xm', name='x-mass'), [ ty('ym', name='y-mass', mass=BALL_MASS) ], ty(1, name='robot_plane'), [ tx('xr', name='x-robot', kinematic=True) ]] system.import_frames(frames) trep.potentials.Gravity(system, (0, -g, 0)) trep.forces.Damping(system, 0.05) # add string constraint as a kinematic configuration var trep.constraints.Distance(system, 'y-mass', 'x-robot','r') return system
def whisker_frames(self, curvature): """ Creates a list of frames that define the whisker. """ if curvature is None: ref_angles = np.zeros(self.num_links) else: ref_angles = get_angles_from_curvature(self.lengths, curvature) frames = [] for j in reversed(range(1, self.num_links)): frames = [ty(self.lengths[j], name='Link-%d' %j), frames] frames = [rx('theta-%d' %j), frames] frames = [rx(ref_angles[j]), frames] frames = [ty(self.lengths[0], name='Link-0'), frames] frames = [tz('z'), [ty('y', name='Base_Point'), frames]] frames = [rx('theta-0'), frames] frames = [rx(ref_angles[0]), frames] return frames
def whisker_frames(self): """Creates a list of frames that define the whisker.""" x0, y0, z0, th_x0, th_y0, th_z0 = extract_angles(self._ref) L = self._link_length frames = [] for j in reversed(range(1, self.num_links)): frames = [tx(L, name='Link-%d' %j), frames] frames = [rz('theta_z-%d' %j), [ry('theta_y-%d' %j), frames]] frames = [rz(th_z0[j]),[ry(th_y0[j]),frames]] frames = [tx(L, name='Link-0'), frames] frames = [tx('xb'), [ty('yb'), [tz('zb', name='Rotated_Base_Point'), frames]]] frames = [rz('theta_z-0'), [ry('theta_y-0'), [rx('theta_x-0'), frames]]] frames = [rz(th_z0[0]),[ry(th_y0[0]), [rx(th_x0[0]), frames]]] frames = [tx(x0), [ty(y0), [tz(z0, name='Base_Point'), frames]]] return frames
def whisker_frames(self, curvature): """ Creates a list of frames that define the whisker. """ if curvature is None: ref_angles = np.zeros(self.num_links) else: ref_angles = get_angles_from_curvature(self.lengths, curvature) frames = [] for j in reversed(range(1, self.num_links)): frames = [ty(self.lengths[j], name='Link-%d' % j), frames] frames = [rx('theta-%d' % j), frames] frames = [rx(ref_angles[j]), frames] frames = [ty(self.lengths[0], name='Link-0'), frames] frames = [tz('z'), [ty('y', name='Base_Point'), frames]] frames = [rx('theta-0'), frames] frames = [rx(ref_angles[0]), frames] return frames
def build_system(): system = trep.System() frames = [ tx('xs', name='x-stylus', kinematic=True), [ ty('ys', name='y-stylus', kinematic=True), [ tz('zs', name='z-stylus', kinematic=True)]], tx('xm', name='x-mass'), [ ty('ym', name='y-mass'), [ tz('zm', name=MASSFRAME, mass=M)]]] system.import_frames(frames)#### adds children frame to the world frame system trep.constraints.Distance(system, MASSFRAME, 'z-stylus', L, name="Link") ###enforces constraint between between the mass frame and the end of the stylus ###use two PointOnPlane constraints to constrain point to a line ###trep.constraints.PointOnPlane(system, MASSFRAME, 'z-stylus', L, name="Link") ###enforces constraint between between the mass frame and the end of the stylus trep.potentials.Gravity(system, (0,0,-g)) trep.forces.Damping(system, B) return system
def create_system(self): # define system: system = trep.System() frames = [ tx('xm', name='x-mass'), [ ty('ym', name='y-mass'), [ tz('zm', name='z-mass', mass=self.mass) ]], ty(h0, name='robot_plane'), [ tx('xr', name='x-robot', kinematic=True), [ tz('zr', name='z-robot', kinematic=True) ]]] system.import_frames(frames) trep.potentials.Gravity(system, (0, -g, 0)) trep.forces.Damping(system, 0.05) # add string constraint as a kinematic configuration var trep.constraints.Distance(system, 'z-mass', 'z-robot','r') return system
def whisker_frames(self, curvature, base_pos, base_rot): """ Creates a list of frames that define the whisker. """ if curvature is None: ref_angles = np.zeros(self.num_links) else: ref_angles = get_angles_from_curvature(self.lengths, curvature) frames = [] for j in reversed(range(1, self.num_links)): frames = [tx(self.lengths[j], name='Link-%d' % j), frames] frames = [rz('theta-%d_z' % j), frames] frames = [ry('theta-%d_y' % j), frames] #frames = [rx('theta-%d_x' %j), frames] frames = [rz(-ref_angles[j]), frames] frames = [tx(self.lengths[0], name='Link-0'), frames] frames = [rz('theta-0_z', name='Moving Base Point'), frames] frames = [ry('theta-0_y'), frames] frames = [rx('theta-0_x'), frames] frames = [tz('z'), [ty('y'), [tx('x'), frames]]] (X, Y, Z) = base_pos (theta, phi, zeta) = base_rot # Rotate to the correct position. frames = [rz(theta), [ry(phi), [rx(zeta), frames]]] # Place the whisker at the correct spot on the mystacial pad and add an angle # that drives the whisking motion. frames = [ tx(X), [ ty(Y), [ tz(Z, name='Base Point'), [rz('Driving Angle', name="Driving Angle"), frames] ] ] ] frames = [rz(0.0, name='Head'), frames] return frames
def build_system(): sys = trep.System() frames = [ ty('yc',name=CARTFRAME, mass=M), [ rx('theta', name="pendulumShoulder"), [ tz(L, name=MASSFRAME, mass=M)]]] sys.import_frames(frames) trep.potentials.Gravity(sys, (0,0,-g)) trep.forces.Damping(sys, B) trep.forces.ConfigForce(sys,'yc','cart-force') return sys
def build_system(torque_force=False): sys = trep.System() frames = [ tx('xs', name=XCARTFRAME, kinematic=True), [ ty('yc',name=CARTFRAME, mass=M,kinematic=True), [ rx('theta', name="Shoulder1"), [ ry('phi',name="shoulder2"),[ tz(L, name=MASSFRAME, mass=M)]]]]] sys.import_frames(frames) trep.potentials.Gravity(sys, (0,0,-g)) trep.forces.Damping(sys, B) if torque_force: trep.forces.ConfigForce(sys, 'theta', 'theta-force') return sys
def build_system(torque_force=False): cart_mass = 10.0 pendulum_length = 1.0 pendulum_mass = 1.0 system = trep.System() frames = [ tx('x', name='Cart', mass=cart_mass), [ rz('theta', name="PendulumBase"), [ ty(-pendulum_length, name="Pendulum", mass=pendulum_mass)]]] system.import_frames(frames) trep.potentials.Gravity(system, (0, -9.8, 0)) trep.forces.Damping(system, 0.01) trep.forces.ConfigForce(system, 'x', 'x-force') if torque_force: trep.forces.ConfigForce(system, 'theta', 'theta-force') return system
def make_string_constraints(self): for name, hook_point in self.string_hooks.iteritems(): info = { 'name' : name, 'x' : name + '-x', # Name of X kinematic config variable 'y' : name + '-y', # Name of Y kinematic config variable 'length' : name + '-length', # Name of length kinematic config variable # Name of the frames connected by the strings 'control_hook' : name + '_control', 'hook' : hook_point } # Add frames from the control_hook self.string_plane.import_frames([ tx(info['x'], kinematic=True), [ ty(info['y'], kinematic=True, name=info['control_hook']) ]]) trep.constraints.Distance(self, info['hook'], info['control_hook'], info['length'], name=name) self.string_constraints[name] = info
def make_string_constraints(self): for name, hook_point in self.string_hooks.iteritems(): info = { 'name': name, 'x': name + '-x', # Name of X kinematic config variable 'y': name + '-y', # Name of Y kinematic config variable 'length': name + '-length', # Name of length kinematic config variable # Name of the frames connected by the strings 'control_hook': name + '_control', 'hook': hook_point } # Add frames from the control_hook self.string_plane.import_frames([ tx(info['x'], kinematic=True), [ty(info['y'], kinematic=True, name=info['control_hook'])] ]) trep.constraints.Distance(self, info['hook'], info['control_hook'], info['length'], name=name) self.string_constraints[name] = info
if q1 == self.config and q2 == self.config: return self.k else: return 0.0 def V_dqdqdq(self, q1, q2, q3): return 0.0 tf = 10.0 dt = 0.01 # Here we define the mechanical system system = trep.System() frames = [ ty(3), # Provided as an angle reference rx("theta"), [ty(3, mass=1)] ] system.import_frames(frames) #trep.potentials.Gravity(system, (0, 0, -9.8)) PyConfigSpring(system, 'theta', x0=0.7, k=20) trep.forces.Damping(system, 1.2) # These are the initial conditions for the variational integrator. q0 = [0] q1 = [0] # Now we create and initialize a variational integrator for the system. mvi = trep.MidpointVI(system) mvi.initialize_from_configs(0.0, q0, dt, q1)
D = 3.0 * 0.0254 # wheel diamater in meters # transform from center of geometry of the cover out to the string hooks. The # base frame has x forward, y out the left side of the robot, and z out the top # (all in the robot's pov). cover_to_left_string = [-0.010, 0.039, 0.041] cover_to_right_string = [-0.010, -0.039, 0.041] ################################################################################ # Now we are ready to define the system ################################################################################ system = trep.System() frames = [ ###### PUPPET ###### tx('TorsoX'), [ ty('TorsoY'), [ tz('TorsoZ'), [ rz('TorsoPsi'), [ ry('TorsoTheta'), [ rx('TorsoPhi', name='Torso'), [ tz(-torso_height_2 / 2, mass=torso_mass), tx(-torso_width_1 / 2), [tz(torso_height_3, name='RightShoulderHook')], tx(torso_width_1 / 2), [tz(torso_height_3, name='LeftShoulderHook')], tz(torso_height_4, name='Head'),
d = 0.01 #m dw = 0.1 #m LEFTWHISK = "Left whisker" RIGHTWHISK = "Right whisker" Aw = math.pi/3 An = math.pi/3 #(math.pi/2.0) q0= np.array([0,0,0]) # dq0 = np.array([0,0,0]) system = trep.System() frames = [#1 rx('theta', name ="neck",kinematic=True),[#2 tz(Hp, name = 'head', mass = MH),[#3 ty(-d,name = "Lcheek"),[ rx('phiL',name = LEFTWHISK, kinematic = True),[ ty(-dw, name = "Lwhisk", mass = MW)]], ty(d,name = "Rcheek"),[ rx('phiR',name = RIGHTWHISK, kinematic = True),[ ty(dw, name = "Rwhisk", mass = MW)]]]]] system.import_frames(frames) trep.potentials.Gravity(system,(0,0,-g)) trep.forces.Damping(system,B) print "configs",system.configs def proj_func(x): x[0] = np.fmod(x[0]+np.pi, 2.0*np.pi) if(x[0] < 0):
# define initial config and velocity q0 = np.array([0, np.pi]) # q = [x_cart, theta] dq0 = np.array([0, 0]) # dq = [xdot, thetadot] # define time parameters: dt = 0.0167 tf = 10.0 # create system system = trep.System() # define frames frames = [ trep.tx("x_cart", name="CartFrame", mass=mc), [ trep.rz("theta", name="PendulumBase"), [trep.ty(l, name="Pendulum", mass=m)] ] ] # add frames to system system.import_frames(frames) # add gravity potential trep.potentials.Gravity(system, (0, -g, 0)) # add a horizontal force on the cart trep.forces.ConfigForce(system, "x_cart", "cart_force") ############# # SAC STUFF # ############# def proj_func(x):
# This script simulates a damped pendulum with a single link. import sys import trep from trep import tx,ty,tz,rx,ry,rz import trep.constraints import trep.visual as visual tf = 10.0 dt = 0.01 # Here we define the mechanical system system = trep.System() frames = [ ty(3), # Provided as an angle reference rx("theta"), [tz(-3, mass=1)] ] system.import_frames(frames) trep.potentials.Gravity(system, (0, 0, -9.8)) trep.forces.Damping(system, 1.2) # These are the initial conditions for the variational integrator. q0 = (0.23,) # Note the comma, this is how you create a tuple with q1 = (0.24,) # a single element # Now we create and initialize a variational integrator for the system. mvi = trep.MidpointVI(system) mvi.initialize_from_configs(0.0, q0, dt, q1) # This is the actual simulation loop. We will store the results in # two lists.
# This is our simulation loop. We save the results in two lists. q = [mvi.q2] t = [mvi.t2] while mvi.t1 < tf: mvi.step(mvi.t2 + dt) q.append(mvi.q2) t.append(mvi.t2) return (t, q) system = trep.System() system.import_frames([ rx('theta1'), [tz(2, mass=1, name='pend1')], ty(1), [rx('theta2'), [tz(2, mass=1, name='pend2')]] ]) trep.potentials.LinearSpring(system, 'pend1', 'pend2', k=20, x0=1) trep.forces.LinearDamper(system, 'pend1', 'pend2', c=1) trep.potentials.Gravity(system, name="Gravity") system.q = [3, -3] # Simulate start = time.clock() (t, q) = simulate_system(system) finish = time.clock() # Display print "Simulation: dt=%f, tf=%f, runtime=%f s" % (dt, tf, finish - start)
import trep.visual as visual tf = 10.0 dt = 0.01 # Define the mechanical system system = trep.System() frames = [ rx('J', name='J'), [ tz(-0.5, name='I', mass=1), tz(-1), [ rx('H', name='H'), [ tz(-1, name='G', mass=1), tz(-2, name='O2')]]], ty(1.5), [ rx('K', name='K'), [ tz(-1, name='L', mass=1), tz(-2), [ rx('M', name='M'), [ tz(-0.5, name='N', mass=1), tz(-1.0, name='O')]]]], ty(-1.5), [ rx('A', name='A'), [ tz(-1, name='B', mass=1), tz(-2), [ rx('C', name='C'), [ tz(-0.375, name='D', mass=1), tz(-0.75), [ rx('E', name='E'), [ tz(-0.5, name='F', mass=1),
# set mass, length, and gravity: m = 1.0; l = 1.0; g = 9.8; # set state and step conditions: pk = 0.5 # discrete generalized momentum qk = 0.2 # theta config uk = 0.8 # input torque dt = 0.1 # timestep # create system system = trep.System() # define frames frames = [ trep.rz("theta_1", name="PendAngle"), [ trep.ty(-l, name="PendMass", mass=m)]] # add frames to system system.import_frames(frames) # add gravity potential trep.potentials.Gravity(system, (0,-g,0)) # add a torque at the base trep.forces.ConfigForce(system, "theta_1", "tau") # create and initialize variational integrator mvi = trep.MidpointVI(system) mvi.initialize_from_state(0, np.array([qk]), np.array([pk])) # take single step with VI: mvi.step(mvi.t1+dt, np.array([uk])) # args are t2, u1 # calc derivatives of discrete Lagrangian:
def make_skeleton(dimensions={}, joints={}): dim = fill_dimensions(dimensions) joints = fill_joints(joints) frames = [ tx(joints['torso_tx']), [ ty(joints['torso_ty']), [ tz(joints['torso_tz']), [ rz(joints['torso_rz']), [ ry(joints['torso_ry']), [ rx(joints['torso_rx'], name='pelvis', mass=dim['pelvis_mass']), [ tx(-dim['lhip_width'], name='lhip'), [ rz(joints['lhip_rz']), [ ry(joints['lhip_ry']), [ rx(joints['lhip_rx'], name='lfemur'), [ tz(-dim['lfemur_length'] / 2, name='lfemur_mass', mass=dim['femur_mass']), tz(-dim['lfemur_length'], name='lfemur_end'), [ rx(joints['lknee_rx'], name='ltibia'), [ tz(-dim['ltibia_length'] / 2, name='ltibia_mass', mass=dim[ 'tibia_mass']), tz(-dim[ 'ltibia_length'], name='ltibia_end'), [ rz(joints[ 'lfoot_rz']), [ ry(joints[ 'lfoot_ry'] ), [ rx(joints[ 'lfoot_rx'], name= 'lfoot' ), [ ty(dim[ 'lfoot_length'], name= 'lfoot_end' ) ] ] ] ] ] ] ] ] ] ], tx(dim['rhip_width'], name='rhip'), [ rz(joints['rhip_rz']), [ ry(joints['rhip_ry']), [ rx(joints['rhip_rx'], name='rfemur'), [ tz(-dim['rfemur_length'] / 2, name='rfemur_mass', mass=dim['femur_mass']), tz(-dim['rfemur_length'], name='rfemur_end'), [ rx(joints['rknee_rx'], name='rtibia'), [ tz(-dim['rtibia_length'] / 2, name='rtibia_mass', mass=dim[ 'tibia_mass']), tz(-dim[ 'rtibia_length'], name='rtibia_end'), [ rz(joints[ 'rfoot_rz']), [ ry(joints[ 'rfoot_ry'] ), [ rx(joints[ 'rfoot_rx'], name= 'r_foot' ), [ ty(dim[ 'rfoot_length'], name= 'rfoot_end' ) ] ] ] ] ] ] ] ] ] ], tz(dim['upper_torso_length'], name='spine_top'), [ tz(dim['neck_length'], name='neck'), [ rz(joints['neck_rz']), [ ry(joints['neck_ry']), [ rx(joints['neck_rz'], name='neck_joint'), [ tz(dim[ 'lower_head_length'], name='head'), [ tz(dim[ 'upper_head_length'], name='head_center', mass=dim[ 'head_mass']), [ tz(dim[ 'final_head_length'], name='head_end') ] ] ] ] ] ], tx(-dim['lshoulder_width'], name='lshoulder'), [ rz(joints['lshoulder_rz']), [ ry(joints['lshoulder_ry']), [ rx(joints['lshoulder_rx'], name='lhumerus'), [ tz(-dim['lhumerus_length'] / 2, name='lhumerus_mass', mass=dim['humerus_mass'] ), tz(-dim['lhumerus_length'], name='lhumerus_end'), [ rx(joints['lelbow_rx'], name='lradius'), [ tz(-dim[ 'lradius_length'] / 2, name= 'lradius_mass', mass=dim[ 'radius_mass'] ), tz(-dim[ 'lradius_length'], name= 'lradius_end'), [ rz(joints[ 'lhand_rz'] ), [ ry(joints[ 'lhand_ry'] ), [ rx(joints[ 'lhand_rx'], name= 'lhand' ), [ tz(-dim[ 'lhand_length'], name ='lhand_end' ) ] ] ] ] ] ] ] ] ] ], tx(dim['rshoulder_width'], name='rshoulder'), [ rz(joints['rshoulder_rz']), [ ry(joints['rshoulder_ry']), [ rx(joints['rshoulder_rx'], name='right_humerus'), [ tz(-dim['rhumerus_length'] / 2, name='rhumerus_mass', mass=dim['humerus_mass'] ), tz(-dim['rhumerus_length'], name='rhumerus_end'), [ rx(joints['relbow_rx'], name='rradius'), [ tz(-dim[ 'rradius_length'] / 2, name= 'rradius_mass', mass=dim[ 'radius_mass'] ), tz(-dim[ 'rradius_length'], name= 'rradius_end'), [ rz(joints[ 'rhand_rz'] ), [ ry(joints[ 'rhand_ry'] ), [ rx(joints[ 'rhand_rx'], name= 'right_hand' ), [ tz(-dim[ 'rhand_length'], name ='right_hand_end' ) ] ] ] ] ] ] ] ] ] ] ] ] ] ] ] ] ] ] return frames
""" Not working because cosine surface not rewritten yet. """ import trep from trep import ty, tz, rx from trep.visual import * import numpy as np import trep_collisions as tc # Create the system. ball = trep.System() ball.import_frames([ty('y'), [tz('z', mass=1.0)]]) trep.potentials.Gravity(ball) # Create the surface. surface = tc.surfaces.Cosine(ball, 1, 1) # Initialize the integrator. mvi = tc.CollisionMVI(ball, surface) # Give the initial condition. ball.get_config('z').q = 7.0 ball.get_config('y').q = 0.5 mvi.initialize_state(0.0, ball.q, tc.util.D2L2(mvi)) # Simulate. tf = 5.0 dt = 0.01 (t, q, lam) = tc.simulate(mvi, tf, dt)
D = 3.0*0.0254 # wheel diamater in meters # transform from center of geometry of the cover out to the string hooks. The # base frame has x forward, y out the left side of the robot, and z out the top # (all in the robot's pov). cover_to_left_string = [-0.010, 0.039, 0.041] cover_to_right_string = [-0.010, -0.039, 0.041] ################################################################################ # Now we are ready to define the system ################################################################################ system = trep.System() frames = [ ###### PUPPET ###### tx('TorsoX'), [ty('TorsoY'), [tz('TorsoZ'), [ rz('TorsoPsi'), [ry('TorsoTheta'), [rx('TorsoPhi',name='Torso'), [ tz(-torso_height_2/2, mass=torso_mass), tx(-torso_width_1/2), [tz(torso_height_3, name='RightShoulderHook')], tx( torso_width_1/2), [tz(torso_height_3, name= 'LeftShoulderHook')], tz(torso_height_4, name='Head'), [tz(head_length/2, mass=head_mass)], # Define the left arm tx(torso_width/2), [tz(torso_height_1), [ rz('LShoulderPsi'), [ry('LShoulderTheta'), [rx('LShoulderPhi', name='LeftShoulder'), [ tz(-humerus_length/2, name='LeftHumerus', mass=humerus_mass), tz(-humerus_length), [ rx('LElbowPhi', name='LeftElbow'), [ tz(-radius_length/2, name='LeftRadius', mass=radius_mass), tz(-radius_length), [ tz(-hand_length/2, mass=hand_mass), tz(-hand_length, name='LeftFinger')]]]]]]]],
# This is our simulation loop. We save the results in two lists. q = [mvi.q2] t = [mvi.t2] while mvi.t1 < tf: mvi.step(mvi.t2+dt) q.append(mvi.q2) t.append(mvi.t2) return (t,q) system = trep.System() system.import_frames([ rx('theta1'), [ tz(2, mass=1, name='pend1') ], ty(1), [ rx('theta2'), [ tz(2, mass=1, name='pend2') ]] ]) trep.potentials.LinearSpring(system, 'pend1', 'pend2', k=20, x0=1) trep.forces.LinearDamper(system, 'pend1', 'pend2', c=1) trep.potentials.Gravity(system, name="Gravity") system.q = [3,-3] # Simulate start = time.clock() (t, q) = simulate_system(system) finish = time.clock()
dt = 0.01 tf = 10.0 # Set up the system frames system = trep.System() system.import_frames([ # Define the 3 Center Links rx('theta1', kinematic=True),[ tz(-0.75, name='pend1'),[ rx('theta2'),[ tz(-0.75, name='pend2'),[ rx('theta3'),[ tz(-0.5, name='legConnection'),[ tz(-0.5, mass=1, name='COMLeg'),[ tz(-1, name='pend3')]]]]]]], # Define the 2 Right Links ty(1), [ rx('theta4', kinematic=True),[ tz(-0.5, mass=1, name='COM4'),[ tz(-0.5),[ rx('theta5'),[ tz(-1, name='pend5')]]]]], # Define the 2 Left Links ty(-1), [ rx('theta6', kinematic=True),[ tz(-0.5, mass=1, name='COM6'),[ tz(-0.5, name='pend6'),[ rx('theta7'),[ tz(-1, name='pend7') ] ] ]
tz(-0.7, name='pend2'), [ rx('theta3'), [ tz(-0.5, name='legConnection'), [ tz(-0.5, mass=1, name='COMLeg'), [tz(-1, name='pend3')] ] ] ] ] ] ], # Define the 2 Right Links ty(1), [ rx('theta4', kinematic=True), [ tz(-0.5, mass=1, name='COM4'), [tz(-0.5), [rx('theta5'), [tz(-1, name='pend5')]]] ] ], # Define the 2 Left Links ty(-1), [ rx('theta6', kinematic=True), [ tz(-0.5, mass=1, name='COM6'), [tz(-0.5, name='pend6'), [rx('theta7'), [tz(-1, name='pend7')]]] ]
tz(-L4, name='pend2'), [ rx('theta3'), [ tz(-L7, name='legConnection'), [ tz(-(((L7 + L8) / 2) - L7), mass=1, name='COMLeg'), [tz(-((L7 + L8) / 2), name='pend3')] ] ] ] ] ] ], # Define the 2 Right Links ty(B1x), [ tz(B1y), [ rx('theta4'), [ tz(-L5 / 2, mass=1, name='COM4'), [tz(-L5 / 2), [rx('theta5'), [tz(-L6, name='pend5')]]] ] ] ], # Define the 2 Left Links ty(-B2x), [ tz(B2y), [
def make_frames(self, m, a): return [ty('y'), [tz('z', mass=0.2*m, name='center'), [rx('theta', mass=(0, m*a**2/6, 0, 0)), [rx(0.0), [tz(a, mass=0.2*m)], rx(np.radians(120)), [tz(a, mass=0.2*m)], rx(np.radians(240)), [tz(a, mass=0.2*m)]]]]]
rx('center_theta1'), [ tz(-0.0856, name='center_link2'), [ rx('center_theta2'), [ tz(-0.0691, mass=0, name='center_attach'), [tz(-0.1016, name='foot', mass=0)] ] ] ] ] ] ], # right links ty(0.0573), [ tz(-0.0918), [ rx('motor2', name='motor2'), [ tz(-0.0657, name='right_link'), [rx('right_theta'), [tz(-0.1517, name='right_attach')]] ] ] ], # left links ty(-0.0573), [ tz(-0.0918), [
import numpy as np from numpy import matrix, array import scipy from scipy.integrate import odeint import trep.visual as visual # Define the length of the simulation and the time step. tf = 10.0 dt = 0.01 system = trep.System() frames = [ tx('TorsoX'), [ ty('TorsoY'), [ tz('TorsoZ'), [ rz('TorsoPsi'), [ ry('TorsoTheta'), [ rx('TorsoPhi', name='Torso'), [ tz(-1.5, mass=50), tx(-1.011), [tz(0.658, name='Right Torso Hook')], tx(1.011), [tz(0.658, name='Left Torso Hook')], tz(0.9, name='Head'),
# This is a basic humanoid puppet with a fixed head. It has no # inputs. import sys import trep from trep import tx, ty, tz, rx, ry, rz import trep.visual as visual # Set the length of simulation and the time step. tf = 10.0 dt = 0.01 # Define the puppet's mechanical structure system = trep.System() frames = [ tx('TorsoX'), [ty('TorsoY'), [tz('TorsoZ'), [ rz('TorsoPsi'), [ry('TorsoTheta'), [rx('TorsoPhi',name='Torso'), [ tz(-1.5, mass=50), tx(-1.011), [tz(0.658, name='Right Torso Hook')], tx( 1.011), [tz(0.658, name= 'Left Torso Hook')], tz(0.9, name='Head'), [tz(0.5, mass=(10,1,1,1))], # Define the left arm tx(1.3), [tz(0.4), [ rz('LShoulderPsi'), [ry('LShoulderTheta'), [rx('LShoulderPhi', name='Left Shoulder'), [ tz(-0.95, name='Left Humerus', mass=(5,1,1,1)), tz(-1.9), [ rx('LElbowTheta', name='Left Elbow'), [ tz(-1, name='Left Radius', mass=(4,1,1,1)), tz(-2.001), [tx(0.14), [ty(-0.173, name='Left Finger')]]]]]]]]], # Define the right arm tx(-1.3), [tz(0.4), [
import numpy as np import trep # set mass, length, and gravity: m = 1.0; l = 1.0; g = 9.8; # create system system = trep.System() # define frames frames = [ trep.rz("theta_1", name="Link1"), [ trep.ty(-l, name="Mass1", mass=m), [ trep.rz("theta_2", name="Link2"), [ trep.ty(-l, name="Mass2", mass=m)]]], trep.tx(2*l, name="Link3Anchor")] # add frames to system system.import_frames(frames) # add link 3 as a distance constraint trep.constraints.Distance(system, "Mass2", "Link3Anchor", l) # set gravity trep.potentials.Gravity(system, (0, -g, 0)) # add and set torque input on theta_1 trep.forces.ConfigForce(system, "theta_1", "torque1") system.get_input('torque1').u = 2.0 # solve for equilibrium configuration
B=0.002 #damping MH = 0.5 #kg MUL =0.2 #kg MLL = 0.1 #kg UL = 0.25 #m LL = 0.25 #m HIP = "hip joint" ULEG = "UpperLeg" LLEG = "LowerLeg" system = trep.System() frames = [#1 ty('yb', name ="body", mass = MH),[#2 rx('theta1', name = HIP,),[#3 tz(-UL ,name = ULEG, mass = MUL),[ rx('theta2', name = 'knee'),[ tz(-LL, name = LLEG, mass = MLL)]]]]] system.import_frames(frames) trep.potentials.Gravity(system,(0,0,-g)) trep.forces.Damping(system,B) trep.forces.ConfigForce(system, 'theta1','hip-torque') print "configs",system.nu q0= np.array([0,-np.pi/2,0]) # dq0 = np.array([0,0,0])
import trep.visual as visual tf = 10.0 dt = 0.01 # Define the mechanical system system = trep.System() frames = [ rx('J', name='J'), [ tz(-0.5, name='I', mass=1), tz(-1), [rx('H', name='H'), [tz(-1, name='G', mass=1), tz(-2, name='O2')]] ], ty(1.5), [ rx('K', name='K'), [ tz(-1, name='L', mass=1), tz(-2), [ rx('M', name='M'), [tz(-0.5, name='N', mass=1), tz(-1.0, name='O')] ] ] ], ty(-1.5), [ rx('A', name='A'),
# This script simulates a pendulum with a single link driven by # a torsional spring instead of gravity. import sys import trep from trep import tx,ty,tz,rx,ry,rz import trep.constraints import trep.visual as visual tf = 10.0 dt = 0.01 # Here we define the mechanical system system = trep.System() frames = [ ty(3), # Provided as an angle reference rx("theta"), [ty(3, mass=1)] ] system.import_frames(frames) trep.potentials.ConfigSpring(system, 'theta', k=20, q0=0.6) # These are the initial conditions for the variational integrator. q0 = (0,) # Note the comma, this is how you create a tuple with q1 = (0,) # a single element # Now we create and initialize a variational integrator for the system. mvi = trep.MidpointVI(system) mvi.initialize_from_configs(0.0, q0, dt, q1) # This is the actual simulation loop. We will store the results in # two lists.