/
pace.py
207 lines (182 loc) · 8.65 KB
/
pace.py
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
import robotoc
import numpy as np
import math
path_to_urdf = '../anymal_b_simple_description/urdf/anymal.urdf'
contact_frames = ['LF_FOOT', 'LH_FOOT', 'RF_FOOT', 'RH_FOOT']
contact_types = [robotoc.ContactType.PointContact for i in range(4)]
baumgarte_time_step = 0.04
robot = robotoc.Robot(path_to_urdf, robotoc.BaseJointType.FloatingBase,
contact_frames, contact_types, baumgarte_time_step)
LF_foot_id, LH_foot_id, RF_foot_id, RH_foot_id = robot.contact_frames()
dt = 0.02
step_length = np.array([0.25, 0, 0])
step_height = 0.1
swing_time = 0.24
double_support_time = 0.04
t0 = 0.1
cycle = 3
# Create the cost function
cost = robotoc.CostFunction()
q_standing = np.array([0, 0, 0.4792, 0, 0, 0, 1,
-0.1, 0.7, -1.0,
-0.1, -0.7, 1.0,
0.1, 0.7, -1.0,
0.1, -0.7, 1.0])
q_weight = np.array([0, 0, 0, 250000, 250000, 250000,
0.0001, 0.0001, 0.0001,
0.0001, 0.0001, 0.0001,
0.0001, 0.0001, 0.0001,
0.0001, 0.0001, 0.0001])
v_weight = np.array([100, 100, 100, 100, 100, 100,
1, 1, 1,
1, 1, 1,
1, 1, 1,
1, 1, 1])
u_weight = np.full(robot.dimu(), 1.0e-01)
qi_weight = np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
100, 100, 100,
100, 100, 100,
100, 100, 100,
100, 100, 100])
vi_weight = np.full(robot.dimv(), 100)
config_cost = robotoc.ConfigurationSpaceCost(robot)
config_cost.set_q_ref(q_standing)
config_cost.set_q_weight(q_weight)
config_cost.set_qf_weight(q_weight)
config_cost.set_qi_weight(qi_weight)
config_cost.set_v_weight(v_weight)
config_cost.set_vf_weight(v_weight)
config_cost.set_vi_weight(vi_weight)
config_cost.set_u_weight(u_weight)
cost.push_back(config_cost)
robot.forward_kinematics(q_standing)
x3d0_LF = robot.frame_position(LF_foot_id)
x3d0_LH = robot.frame_position(LH_foot_id)
x3d0_RF = robot.frame_position(RF_foot_id)
x3d0_RH = robot.frame_position(RH_foot_id)
LF_t0 = t0 + swing_time + double_support_time
LH_t0 = t0 + swing_time + double_support_time
RF_t0 = t0
RH_t0 = t0
LF_foot_ref = robotoc.PeriodicFootTrackRef(x3d0_LF, step_length, step_height,
LF_t0, swing_time,
swing_time+2*double_support_time, False)
LH_foot_ref = robotoc.PeriodicFootTrackRef(x3d0_LH, step_length, step_height,
LH_t0, swing_time,
swing_time+2*double_support_time, False)
RF_foot_ref = robotoc.PeriodicFootTrackRef(x3d0_RF, step_length, step_height,
RF_t0, swing_time,
swing_time+2*double_support_time, True)
RH_foot_ref = robotoc.PeriodicFootTrackRef(x3d0_RH, step_length, step_height,
RH_t0, swing_time,
swing_time+2*double_support_time, True)
LF_cost = robotoc.TimeVaryingTaskSpace3DCost(robot, LF_foot_id, LF_foot_ref)
LH_cost = robotoc.TimeVaryingTaskSpace3DCost(robot, LH_foot_id, LH_foot_ref)
RF_cost = robotoc.TimeVaryingTaskSpace3DCost(robot, RF_foot_id, RF_foot_ref)
RH_cost = robotoc.TimeVaryingTaskSpace3DCost(robot, RH_foot_id, RH_foot_ref)
foot_track_weight = np.full(3, 1.0e06)
LF_cost.set_x3d_weight(foot_track_weight)
LH_cost.set_x3d_weight(foot_track_weight)
RF_cost.set_x3d_weight(foot_track_weight)
RH_cost.set_x3d_weight(foot_track_weight)
cost.push_back(LF_cost)
cost.push_back(LH_cost)
cost.push_back(RF_cost)
cost.push_back(RH_cost)
com_ref0 = robot.com()
vcom_ref = 0.5 * step_length / swing_time
com_ref = robotoc.PeriodicCoMRef(com_ref0, vcom_ref, t0, swing_time,
double_support_time, True)
com_cost = robotoc.TimeVaryingCoMCost(robot, com_ref)
com_cost.set_com_weight(np.full(3, 1.0e06))
cost.push_back(com_cost)
# Create the constraints
constraints = robotoc.Constraints(barrier=1.0e-03, fraction_to_boundary_rule=0.995)
joint_position_lower = robotoc.JointPositionLowerLimit(robot)
joint_position_upper = robotoc.JointPositionUpperLimit(robot)
joint_velocity_lower = robotoc.JointVelocityLowerLimit(robot)
joint_velocity_upper = robotoc.JointVelocityUpperLimit(robot)
joint_torques_lower = robotoc.JointTorquesLowerLimit(robot)
joint_torques_upper = robotoc.JointTorquesUpperLimit(robot)
mu = 0.7
friction_cone = robotoc.FrictionCone(robot, mu)
constraints.push_back(joint_position_lower)
constraints.push_back(joint_position_upper)
constraints.push_back(joint_velocity_lower)
constraints.push_back(joint_velocity_upper)
constraints.push_back(joint_torques_lower)
constraints.push_back(joint_torques_upper)
constraints.push_back(friction_cone)
# Create the contact sequence
max_num_each_discrete_events = 2*cycle
contact_sequence = robotoc.ContactSequence(robot, max_num_each_discrete_events)
contact_positions = [x3d0_LF, x3d0_LH, x3d0_RF, x3d0_RH]
contact_status_standing = robot.create_contact_status()
contact_status_standing.activate_contacts([0, 1, 2, 3])
contact_status_standing.set_contact_placements(contact_positions)
contact_sequence.init_contact_sequence(contact_status_standing)
contact_status_rfrh_swing = robot.create_contact_status()
contact_status_rfrh_swing.activate_contacts([0, 1])
contact_status_rfrh_swing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_rfrh_swing, t0)
contact_positions[2] += 0.5 * step_length
contact_positions[3] += 0.5 * step_length
contact_status_standing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_standing, t0+swing_time)
contact_status_lflh_swing = robot.create_contact_status()
contact_status_lflh_swing.activate_contacts([2, 3])
contact_status_lflh_swing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_lflh_swing,
t0+swing_time+double_support_time)
contact_positions[0] += step_length
contact_positions[1] += step_length
contact_status_standing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_standing,
t0+2*swing_time+double_support_time)
for i in range(cycle-1):
t1 = t0 + (i+1)*(2*swing_time+2*double_support_time)
contact_status_rfrh_swing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_rfrh_swing, t1)
contact_positions[2] += step_length
contact_positions[3] += step_length
contact_status_standing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_standing, t1+swing_time)
contact_status_lflh_swing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_lflh_swing,
t1+swing_time+double_support_time)
contact_positions[0] += step_length
contact_positions[1] += step_length
contact_status_standing.set_contact_placements(contact_positions)
contact_sequence.push_back(contact_status_standing,
t1+2*swing_time+double_support_time)
# you can check the contact sequence via
# print(contact_sequence)
T = t0 + cycle*(2*double_support_time+2*swing_time)
N = math.floor(T/dt)
ocp = robotoc.OCP(robot=robot, cost=cost, constraints=constraints,
T=T, N=N, max_num_each_discrete_events=max_num_each_discrete_events)
solver_options = robotoc.SolverOptions()
ocp_solver = robotoc.OCPSolver(ocp=ocp, contact_sequence=contact_sequence,
solver_options=solver_options, nthreads=4)
# Initial time and intial state
t = 0.
q = q_standing
v = np.zeros(robot.dimv())
ocp_solver.set_solution("q", q)
ocp_solver.set_solution("v", v)
f_init = np.array([0.0, 0.0, 0.25*robot.total_weight()])
ocp_solver.set_solution("f", f_init)
ocp_solver.init_constraints(t)
print("Initial KKT error: ", ocp_solver.KKT_error(t, q, v))
ocp_solver.solve(t, q, v)
print("KKT error after convergence: ", ocp_solver.KKT_error(t, q, v))
print(ocp_solver.get_solver_statistics())
# num_iteration = 1000
# robotoc.utils.benchmark.cpu_time(ocp_solver, t, q, v, num_iteration)
viewer = robotoc.utils.TrajectoryViewer(path_to_urdf=path_to_urdf,
base_joint_type=robotoc.BaseJointType.FloatingBase,
viewer_type='gepetto')
viewer.set_contact_info(robot.contact_frames(), mu)
discretization = ocp_solver.get_time_discretization()
viewer.display(discretization.time_steps(), ocp_solver.get_solution('q'),
ocp_solver.get_solution('f', 'WORLD'))