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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51