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


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