talos_conf.py
Go to the documentation of this file.
1 from pathlib import Path
2 
3 import numpy as np
4 import pinocchio as pin
5 from example_robot_data.robots_loader import getModelPath
6 
7 np.set_printoptions(precision=3, linewidth=200, suppress=True)
8 LINE_WIDTH = 60
9 
10 N_SIMULATION = 4000 # number of time steps simulated
11 dt = 0.002 # controller time step
12 
13 lxp = 0.10 # foot length in positive x direction
14 lxn = 0.10 # foot length in negative x direction
15 lyp = 0.065 # foot length in positive y direction
16 lyn = 0.065 # foot length in negative y direction
17 lz = 0.0 # foot sole height with respect to ankle joint
18 mu = 0.3 # friction coefficient
19 fMin = 5.0 # minimum normal force
20 fMax = 1000.0 # maximum normal force
21 rf_frame_name = "leg_right_sole_fix_joint" # right foot frame name
22 lf_frame_name = "leg_left_sole_fix_joint" # left foot frame name
23 contactNormal = np.array(
24  [0.0, 0.0, 1.0]
25 ) # direction of the normal to the contact surface
26 
27 w_com = 1.0 # weight of center of mass task
28 w_am = 1e-3 # weight of angular momentum task
29 w_foot = 1e-1 # weight of the foot motion task
30 w_contact = -1.0 # weight of foot in contact (negative means infinite weight)
31 w_posture = 1e-1 # weight of joint posture task
32 w_forceRef = 1e-5 # weight of force regularization task
33 w_cop = 0.0
34 w_torque_bounds = 1.0 # weight of the torque bounds
35 w_joint_bounds = 0.0
36 
37 gain_vector = np.array( # gain vector for postural task
38  [
39  10.0,
40  5.0,
41  5.0,
42  1.0,
43  1.0,
44  10.0, # lleg #low gain on axis along y and knee
45  10.0,
46  5.0,
47  5.0,
48  1.0,
49  1.0,
50  10.0, # rleg
51  5000.0,
52  5000.0, # chest
53  500.0,
54  1000.0,
55  10.0,
56  10.0,
57  10.0,
58  10.0,
59  100.0,
60  50.0, # larm
61  50.0,
62  100.0,
63  10.0,
64  10.0,
65  10.0,
66  10.0,
67  100.0,
68  50.0, # rarm
69  100.0,
70  100.0,
71  ] # head
72 )
73 masks_posture = np.ones(32)
74 
75 tau_max_scaling = 1.45 # scaling factor of torque bounds
76 v_max_scaling = 0.8
77 
78 kp_contact = 10.0 # proportional gain of contact constraint
79 kp_foot = 10.0 # proportional gain of contact constraint
80 kp_com = 10.0 # proportional gain of center of mass task
81 kp_am = 10.0 # proportional gain of angular momentum task
82 kp_posture = 1.0 # proportional gain of joint posture task
83 
84 viewer = pin.visualize.GepettoVisualizer
85 PRINT_N = 500 # print every PRINT_N time steps
86 DISPLAY_N = 20 # update robot configuration in viwewer every DISPLAY_N time steps
87 CAMERA_TRANSFORM = [
88  4.0,
89  -0.2,
90  0.4,
91  0.5243823528289795,
92  0.518651008605957,
93  0.4620114266872406,
94  0.4925136864185333,
95 ]
96 
97 SPHERE_RADIUS = 0.03
98 REF_SPHERE_RADIUS = 0.03
99 COM_SPHERE_COLOR = (1, 0.5, 0, 0.5)
100 COM_REF_SPHERE_COLOR = (1, 0, 0, 0.5)
101 RF_SPHERE_COLOR = (0, 1, 0, 0.5)
102 RF_REF_SPHERE_COLOR = (0, 1, 0.5, 0.5)
103 LF_SPHERE_COLOR = (0, 0, 1, 0.5)
104 LF_REF_SPHERE_COLOR = (0.5, 0, 1, 0.5)
105 
106 urdf = "/talos_data/robots/talos_reduced.urdf"
107 path = Path(getModelPath(urdf))
108 urdf = path / urdf
109 srdf = path / "talos_data/srdf/talos.srdf"
110 path = path / "../.."
example_robot_data::robots_loader


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