ex_4_conf.py
Go to the documentation of this file.
1 """Created on Thu Apr 18 09:47:07 2019
2 
3 @author: student
4 """
5 
6 from pathlib import Path
7 
8 import numpy as np
9 import pinocchio as pin
10 
11 np.set_printoptions(precision=3, linewidth=200, suppress=True)
12 LINE_WIDTH = 60
13 
14 DATA_FILE_LIPM = "romeo_walking_traj_lipm.npz"
15 DATA_FILE_TSID = "romeo_walking_traj_tsid.npz"
16 
17 # robot parameters
18 # ----------------------------------------------
19 filename = str(Path(__file__).resolve().parent)
20 path = filename + "/../models/romeo"
21 urdf = path + "/urdf/romeo.urdf"
22 srdf = path + "/srdf/romeo_collision.srdf"
23 nv = 37
24 foot_scaling = 1.0
25 lxp = foot_scaling * 0.10 # foot length in positive x direction
26 lxn = foot_scaling * 0.05 # foot length in negative x direction
27 lyp = foot_scaling * 0.05 # foot length in positive y direction
28 lyn = foot_scaling * 0.05 # foot length in negative y direction
29 lz = 0.07 # foot sole height with respect to ankle joint
30 mu = 0.3 # friction coefficient
31 fMin = 0.0 # minimum normal force
32 fMax = 1e6 # maximum normal force
33 rf_frame_name = "RAnkleRoll" # right foot frame name
34 lf_frame_name = "LAnkleRoll" # left foot frame name
35 contactNormal = np.matrix(
36  [0.0, 0.0, 1.0]
37 ).T # direction of the normal to the contact surface
38 
39 # configuration for LIPM trajectory optimization
40 # ----------------------------------------------
41 alpha = 10 ** (2) # CoP error squared cost weight
42 beta = 0 # CoM position error squared cost weight
43 gamma = 10 ** (-1) # CoM velocity error squared cost weight
44 h = 0.58 # fixed CoM height
45 g = 9.81 # norm of the gravity vector
46 foot_step_0 = np.array([0.0, -0.096]) # initial foot step position in x-y
47 dt_mpc = 0.1 # sampling time interval
48 T_step = 1.2 # time needed for every step
49 step_length = 0.05 # fixed step length
50 step_height = 0.05 # fixed step height
51 nb_steps = 4 # number of desired walking steps
52 
53 # configuration for TSID
54 # ----------------------------------------------
55 dt = 0.002 # controller time step
56 T_pre = 1.5 # simulation time before starting to walk
57 T_post = 1.5 # simulation time after walking
58 
59 w_com = 1.0 # weight of center of mass task
60 w_cop = 0.0 # weight of center of pressure task
61 w_am = 1e-4 # weight of angular momentum task
62 w_foot = 1e0 # weight of the foot motion task
63 w_contact = 1e2 # weight of the foot in contact
64 w_posture = 1e-4 # weight of joint posture task
65 w_forceRef = 1e-5 # weight of force regularization task
66 w_torque_bounds = 0.0 # weight of the torque bounds
67 w_joint_bounds = 0.0
68 
69 tau_max_scaling = 1.45 # scaling factor of torque bounds
70 v_max_scaling = 0.8
71 
72 kp_contact = 10.0 # proportional gain of contact constraint
73 kp_foot = 10.0 # proportional gain of contact constraint
74 kp_com = 10.0 # proportional gain of center of mass task
75 kp_am = 10.0 # proportional gain of angular momentum task
76 kp_posture = 1.0 # proportional gain of joint posture task
77 gain_vector = kp_posture * np.ones(nv - 6)
78 masks_posture = np.ones(nv - 6)
79 
80 # configuration for viewer
81 # ----------------------------------------------
82 viewer = pin.visualize.GepettoVisualizer
83 PRINT_N = 500 # print every PRINT_N time steps
84 DISPLAY_N = 20 # update robot configuration in viwewer every DISPLAY_N time steps
85 CAMERA_TRANSFORM = [
86  3.578777551651001,
87  1.2937744855880737,
88  0.8885031342506409,
89  0.4116811454296112,
90  0.5468055009841919,
91  0.6109083890914917,
92  0.3978860676288605,
93 ]


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:16