ex_4_long_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 
10 np.set_printoptions(precision=3, linewidth=200, suppress=True)
11 LINE_WIDTH = 60
12 
13 DATA_FILE_LIPM = "romeo_walking_traj_long_lipm.npz"
14 DATA_FILE_TSID = "romeo_walking_traj_long_tsid.npz"
15 
16 # robot parameters
17 # ----------------------------------------------
18 filename = str(Path(__file__).resolve().parent)
19 path = filename + "/../models/romeo"
20 urdf = path + "/urdf/romeo.urdf"
21 srdf = path + "/srdf/romeo_collision.srdf"
22 lxp = 0.07 # foot length in positive x direction
23 lxn = 0.07 # foot length in negative x direction
24 lyp = 0.05 # foot length in positive y direction
25 lyn = 0.05 # foot length in negative y direction
26 lz = 0.07 # foot sole height with respect to ankle joint
27 mu = 0.3 # friction coefficient
28 fMin = 5.0 # minimum normal force
29 fMax = 1000.0 # maximum normal force
30 rf_frame_name = "RAnkleRoll" # right foot frame name
31 lf_frame_name = "LAnkleRoll" # left foot frame name
32 contactNormal = np.matrix(
33  [0.0, 0.0, 1.0]
34 ).T # direction of the normal to the contact surface
35 
36 # configuration for LIPM trajectory optimization
37 # ----------------------------------------------
38 alpha = 10 ** (2) # CoP error squared cost weight
39 beta = 0 # CoM position error squared cost weight
40 gamma = 10 ** (-1) # CoM velocity error squared cost weight
41 h = 0.58 # fixed CoM height
42 g = 9.81 # norm of the gravity vector
43 foot_step_0 = np.array([0.0, -0.096]) # initial foot step position in x-y
44 dt_mpc = 0.2 # sampling time interval
45 T_step = 0.8 # time needed for every step
46 step_length = 0.2 # fixed step length
47 step_height = 0.05 # fixed step height
48 nb_steps = 6 # number of desired walking steps
49 
50 # configuration for TSID
51 # ----------------------------------------------
52 dt = 0.002 # controller time step
53 T_pre = 1.0 # simulation time before starting to walk
54 T_post = 2.0 # simulation time after walking
55 
56 w_com = 1.0 # weight of center of mass task
57 w_foot = 1e-1 # weight of the foot motion task
58 w_posture = 1e-4 # weight of joint posture task
59 w_forceRef = 1e-5 # weight of force regularization task
60 w_torque_bounds = 0.0 # weight of the torque bounds
61 w_joint_bounds = 0.0
62 
63 tau_max_scaling = 1.55 # scaling factor of torque bounds
64 v_max_scaling = 0.8
65 
66 kp_contact = 10.0 # proportional gain of contact constraint
67 kp_foot = 10.0 # proportional gain of contact constraint
68 kp_com = 10.0 # proportional gain of center of mass task
69 kp_posture = 1.0 # proportional gain of joint posture task
70 
71 # configuration for viewer
72 # ----------------------------------------------
73 PRINT_N = 500 # print every PRINT_N time steps
74 DISPLAY_N = 20 # update robot configuration in viwewer every DISPLAY_N time steps
75 CAMERA_TRANSFORM = [
76  3.578777551651001,
77  1.2937744855880737,
78  0.8885031342506409,
79  0.4116811454296112,
80  0.5468055009841919,
81  0.6109083890914917,
82  0.3978860676288605,
83 ]


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