-
Notifications
You must be signed in to change notification settings - Fork 205
/
task.info
222 lines (192 loc) · 5.75 KB
/
task.info
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
centroidalModelType 1 // 0: FullCentroidalDynamics, 1: Single Rigid Body Dynamics
legged_robot_interface
{
verbose false // show the loaded parameters
useAnalyticalGradientsDynamics false
useAnalyticalGradientsConstraints false
}
model_settings
{
positionErrorGain 20.0
phaseTransitionStanceTime 0.4
verboseCppAd true
recompileLibrariesCppAd true
modelFolderCppAd /tmp/ocs2
}
swing_trajectory_config
{
liftOffVelocity 0.2
touchDownVelocity -0.4
swingHeight 0.1
touchdownAfterHorizon 0.2
swingTimeScale 0.15
}
; multiple_shooting settings
multiple_shooting
{
nThreads 3
dt 0.015
sqpIteration 1
deltaTol 1e-4
g_max 1e-2
g_min 1e-6
inequalityConstraintMu 0.1
inequalityConstraintDelta 5.0
projectStateInputEqualityConstraints true
printSolverStatistics true
printSolverStatus false
printLinesearch false
useFeedbackPolicy true
integratorType RK2
threadPriority 50
}
; DDP settings
ddp
{
algorithm SLQ
nThreads 3
threadPriority 50
maxNumIterations 1
minRelCost 1e-1
constraintTolerance 5e-3
displayInfo false
displayShortSummary false
checkNumericalStability false
debugPrintRollout false
AbsTolODE 1e-5
RelTolODE 1e-3
maxNumStepsPerSecond 10000
timeStep 0.015
backwardPassIntegratorType ODE45
constraintPenaltyInitialValue 20.0
constraintPenaltyIncreaseRate 2.0
preComputeRiccatiTerms true
useFeedbackPolicy false
strategy LINE_SEARCH
lineSearch
{
minStepLength 1e-2
maxStepLength 1.0
hessianCorrectionStrategy DIAGONAL_SHIFT
hessianCorrectionMultiple 1e-5
}
}
; Rollout settings
rollout
{
AbsTolODE 1e-5
RelTolODE 1e-3
timeStep 0.015
integratorType ODE45
maxNumStepsPerSecond 10000
checkNumericalStability false
}
mpc
{
timeHorizon 1.0 ; [s]
solutionTimeWindow -1 ; maximum [s]
coldStart false
debugPrint false
mpcDesiredFrequency 50 ; [Hz]
mrtDesiredFrequency 400 ; [Hz]
}
initialState
{
;; Normalized Centroidal Momentum: [linear, angular] ;;
(0,0) 0.0 ; vcom_x
(1,0) 0.0 ; vcom_y
(2,0) 0.0 ; vcom_z
(3,0) 0.0 ; L_x / robotMass
(4,0) 0.0 ; L_y / robotMass
(5,0) 0.0 ; L_z / robotMass
;; Base Pose: [position, orientation] ;;
(6,0) 0.0 ; p_base_x
(7,0) 0.0 ; p_base_y
(8,0) 0.575 ; p_base_z
(9,0) 0.0 ; theta_base_z
(10,0) 0.0 ; theta_base_y
(11,0) 0.0 ; theta_base_x
;; Leg Joint Positions: [LF, LH, RF, RH] ;;
(12,0) -0.25 ; LF_HAA
(13,0) 0.60 ; LF_HFE
(14,0) -0.85 ; LF_KFE
(15,0) -0.25 ; LH_HAA
(16,0) -0.60 ; LH_HFE
(17,0) 0.85 ; LH_KFE
(18,0) 0.25 ; RF_HAA
(19,0) 0.60 ; RF_HFE
(20,0) -0.85 ; RF_KFE
(21,0) 0.25 ; RH_HAA
(22,0) -0.60 ; RH_HFE
(23,0) 0.85 ; RH_KFE
}
; standard state weight matrix
Q
{
scaling 1e+0
;; Normalized Centroidal Momentum: [linear, angular] ;;
(0,0) 15.0 ; vcom_x
(1,1) 15.0 ; vcom_y
(2,2) 30.0 ; vcom_z
(3,3) 5.0 ; L_x / robotMass
(4,4) 10.0 ; L_y / robotMass
(5,5) 10.0 ; L_z / robotMass
;; Base Pose: [position, orientation] ;;
(6,6) 500.0 ; p_base_x
(7,7) 500.0 ; p_base_y
(8,8) 500.0 ; p_base_z
(9,9) 100.0 ; theta_base_z
(10,10) 200.0 ; theta_base_y
(11,11) 200.0 ; theta_base_x
;; Leg Joint Positions: [LF, LH, RF, RH] ;;
(12,12) 20.0 ; LF_HAA
(13,13) 20.0 ; LF_HFE
(14,14) 20.0 ; LF_KFE
(15,15) 20.0 ; LH_HAA
(16,16) 20.0 ; LH_HFE
(17,17) 20.0 ; LH_KFE
(18,18) 20.0 ; RF_HAA
(19,19) 20.0 ; RF_HFE
(20,20) 20.0 ; RF_KFE
(21,21) 20.0 ; RH_HAA
(22,22) 20.0 ; RH_HFE
(23,23) 20.0 ; RH_KFE
}
; control weight matrix
R
{
scaling 1e-3
;; Feet Contact Forces: [LF, RF, LH, RH] ;;
(0,0) 1.0 ; left_front_force
(1,1) 1.0 ; left_front_force
(2,2) 1.0 ; left_front_force
(3,3) 1.0 ; right_front_force
(4,4) 1.0 ; right_front_force
(5,5) 1.0 ; right_front_force
(6,6) 1.0 ; left_hind_force
(7,7) 1.0 ; left_hind_force
(8,8) 1.0 ; left_hind_force
(9,9) 1.0 ; right_hind_force
(10,10) 1.0 ; right_hind_force
(11,11) 1.0 ; right_hind_force
;; foot velocity relative to base: [LF, LH, RF, RH] (uses the Jacobian at nominal configuration) ;;
(12,12) 5000.0 ; x
(13,13) 5000.0 ; y
(14,14) 5000.0 ; z
(15,15) 5000.0 ; x
(16,16) 5000.0 ; y
(17,17) 5000.0 ; z
(18,18) 5000.0 ; x
(19,19) 5000.0 ; y
(20,20) 5000.0 ; z
(21,21) 5000.0 ; x
(22,22) 5000.0 ; y
(23,23) 5000.0 ; z
}
frictionConeSoftConstraint
{
frictionCoefficient 0.5
; relaxed log barrier parameters
mu 0.1
delta 5.0
}