romeo_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 N_SIMULATION = 4000 # number of time steps simulated
15 dt = 0.002 # controller time step
16 nv = 37
17 
18 lxp = 0.10 # foot length in positive x direction
19 lxn = 0.05 # foot length in negative x direction
20 lyp = 0.05 # foot length in positive y direction
21 lyn = 0.05 # foot length in negative y direction
22 lz = 0.07 # foot sole height with respect to ankle joint
23 mu = 0.3 # friction coefficient
24 fMin = 5.0 # minimum normal force
25 fMax = 1000.0 # maximum normal force
26 rf_frame_name = "RAnkleRoll" # right foot frame name
27 lf_frame_name = "LAnkleRoll" # left foot frame name
28 contactNormal = np.array(
29  [0.0, 0.0, 1.0]
30 ) # direction of the normal to the contact surface
31 
32 w_com = 1.0 # weight of center of mass task
33 w_cop = 0.0 # weight of center of pressure task
34 w_am = 0.0 # weight of angular momentum task
35 w_foot = 1e-1 # weight of the foot motion task
36 w_contact = -1.0 # weight of foot in contact (negative means infinite weight)
37 w_posture = 1e-4 # weight of joint posture task
38 w_forceRef = 1e-5 # weight of force regularization task
39 w_torque_bounds = 1.0 # weight of the torque bounds
40 w_joint_bounds = 0.0
41 
42 tau_max_scaling = 1.45 # scaling factor of torque bounds
43 v_max_scaling = 0.8
44 
45 kp_contact = 10.0 # proportional gain of contact constraint
46 kp_foot = 10.0 # proportional gain of contact constraint
47 kp_com = 10.0 # proportional gain of center of mass task
48 kp_am = 10.0 # proportional gain of angular momentum task
49 kp_posture = 1.0 # proportional gain of joint posture task
50 gain_vector = kp_posture * np.ones(nv - 6)
51 masks_posture = np.ones(nv - 6)
52 
53 viewer = pin.visualize.GepettoVisualizer
54 PRINT_N = 500 # print every PRINT_N time steps
55 DISPLAY_N = 20 # update robot configuration in viwewer every DISPLAY_N time steps
56 CAMERA_TRANSFORM = [
57  4.0,
58  -0.2,
59  0.4,
60  0.5243823528289795,
61  0.518651008605957,
62  0.4620114266872406,
63  0.4925136864185333,
64 ]
65 
66 SPHERE_RADIUS = 0.03
67 REF_SPHERE_RADIUS = 0.03
68 COM_SPHERE_COLOR = (1, 0.5, 0, 0.5)
69 COM_REF_SPHERE_COLOR = (1, 0, 0, 0.5)
70 RF_SPHERE_COLOR = (0, 1, 0, 0.5)
71 RF_REF_SPHERE_COLOR = (0, 1, 0.5, 0.5)
72 LF_SPHERE_COLOR = (0, 0, 1, 0.5)
73 LF_REF_SPHERE_COLOR = (0.5, 0, 1, 0.5)
74 
75 filename = Path(__file__).resolve().parent
76 path = filename / "../models/romeo"
77 urdf = path / "urdf/romeo.urdf"
78 srdf = path / "srdf/romeo_collision.srdf"


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