Skip to content

Commit 9b5aa57

Browse files
committed
Use interpolation in python examples
1 parent 82ab105 commit 9b5aa57

File tree

2 files changed

+32
-20
lines changed

2 files changed

+32
-20
lines changed

examples/go2_fulldynamics.py

Lines changed: 15 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
import numpy as np
22
from bullet_robot import BulletRobot
3-
from simple_mpc import RobotModelHandler, RobotDataHandler, FullDynamicsOCP, MPC, IDSolver, FrictionCompensation
3+
from simple_mpc import RobotModelHandler, RobotDataHandler, FullDynamicsOCP, MPC, IDSolver, FrictionCompensation, Interpolator
44
import example_robot_data as erd
55
import pinocchio as pin
66
import time
@@ -26,6 +26,8 @@
2626
nu = nv - 6
2727
force_size = 3
2828
nk = len(model_handler.getFeetNames())
29+
nf = force_size
30+
2931
gravity = np.array([0, 0, -9.81])
3032
fref = np.zeros(force_size)
3133
fref[2] = -model_handler.getMass() / nk * gravity[2]
@@ -144,6 +146,8 @@
144146

145147
""" Friction """
146148
fcompensation = FrictionCompensation(model_handler.getModel(), True)
149+
""" Interpolation """
150+
interpolator = Interpolator(nq + nv, nv, nu, nf, dt)
147151

148152
""" Initialize simulation"""
149153
device = BulletRobot(
@@ -155,8 +159,6 @@
155159
model_handler.getReferenceState()[:3],
156160
)
157161

158-
nq = mpc.getModelHandler().getModel().nq
159-
nv = mpc.getModelHandler().getModel().nv
160162
device.initializeJoints(model_handler.getReferenceState()[:nq])
161163

162164
for i in range(40):
@@ -237,6 +239,11 @@
237239
force_RL.append(RL_f)
238240
force_RR.append(RR_f)
239241

242+
forces = [total_forces, total_forces]
243+
ddqs = [a0, a1]
244+
xss = [mpc.xs[0], mpc.xs[1]]
245+
uss = [mpc.us[0], mpc.us[1]]
246+
240247
FL_measured.append(mpc.getDataHandler().getFootPose("FL_foot").translation)
241248
FR_measured.append(mpc.getDataHandler().getFootPose("FR_foot").translation)
242249
RL_measured.append(mpc.getDataHandler().getFootPose("RL_foot").translation)
@@ -251,27 +258,24 @@
251258

252259
for j in range(N_simu):
253260
# time.sleep(0.01)
254-
u_interp = (N_simu - j) / N_simu * mpc.us[0] + j / N_simu * mpc.us[1]
255-
a_interp = (N_simu - j) / N_simu * a0 + j / N_simu * a1
256-
x_interp = (N_simu - j) / N_simu * mpc.xs[0] + j / N_simu * mpc.xs[1]
257-
K_interp = (N_simu - j) / N_simu * mpc.Ks[0] + j / N_simu * mpc.Ks[1]
261+
interpolator.interpolate(j / float(N_simu), xss, uss, ddqs, forces)
258262

259263
q_meas, v_meas = device.measureState()
260264
x_measured = np.concatenate([q_meas, v_meas])
261265

262266
mpc.getDataHandler().updateInternalData(x_measured, True)
263267

264-
current_torque = u_interp - 1. * mpc.Ks[0] @ model_handler.difference(
265-
x_measured, x_interp
268+
current_torque = interpolator.u_interpolated - 1. * mpc.Ks[0] @ model_handler.difference(
269+
x_measured, interpolator.x_interpolated
266270
)
267271

268272
qp.solveQP(
269273
mpc.getDataHandler().getData(),
270274
contact_states,
271275
x_measured[nq:],
272-
a0,
276+
interpolator.a_interpolated,
273277
current_torque,
274-
total_forces,
278+
interpolator.forces_interpolated,
275279
mpc.getDataHandler().getData().M,
276280
)
277281

examples/go2_kinodynamics.py

Lines changed: 17 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
import numpy as np
22
from bullet_robot import BulletRobot
3-
from simple_mpc import RobotModelHandler, RobotDataHandler, KinodynamicsOCP, MPC, IDSolver
3+
from simple_mpc import RobotModelHandler, RobotDataHandler, KinodynamicsOCP, MPC, IDSolver, Interpolator
44
import example_robot_data as erd
55
import pinocchio as pin
66
import time
@@ -21,6 +21,10 @@
2121
model_handler.addFoot("RR_foot", base_joint_name, pin.XYZQUATToSE3(np.array([-0.24,-0.15, 0.0, 0,0,0,1])))
2222
data_handler = RobotDataHandler(model_handler)
2323

24+
nq = model_handler.getModel().nq
25+
nv = model_handler.getModel().nv
26+
nu = nv - 6
27+
nf = 12
2428
force_size = 3
2529
nk = len(model_handler.getFeetNames())
2630
gravity = np.array([0, 0, -9.81])
@@ -144,6 +148,9 @@
144148

145149
qp = IDSolver(id_conf, model_handler.getModel())
146150

151+
""" Interpolation """
152+
interpolator = Interpolator(nq + nv, nv, nu, nf, 0.01)
153+
147154
""" Initialize simulation"""
148155
device = BulletRobot(
149156
model_handler.getModel().names,
@@ -155,10 +162,7 @@
155162
)
156163

157164
device.initializeJoints(model_handler.getReferenceState()[:model_handler.getModel().nq])
158-
159165
device.changeCamera(1.0, 60, -15, [0.6, -0.2, 0.5])
160-
nq = mpc.getModelHandler().getModel().nq
161-
nv = mpc.getModelHandler().getModel().nv
162166

163167
q_meas, v_meas = device.measureState()
164168
x_measured = np.concatenate([q_meas, v_meas])
@@ -234,6 +238,11 @@
234238
forces1 = mpc.us[1][: nk * force_size]
235239
contact_states = mpc.ocp_handler.getContactState(0)
236240

241+
forces = [forces0, forces1]
242+
ddqs = [a0, a1]
243+
xss = [mpc.xs[0], mpc.xs[1]]
244+
uss = [mpc.us[0], mpc.us[1]]
245+
237246
device.moveQuadrupedFeet(
238247
mpc.getReferencePose(0, "FL_foot").translation,
239248
mpc.getReferencePose(0, "FR_foot").translation,
@@ -243,21 +252,20 @@
243252

244253
for j in range(N_simu):
245254
# time.sleep(0.01)
255+
interpolator.interpolate(j / float(N_simu), xss, uss, ddqs, forces)
256+
246257
q_meas, v_meas = device.measureState()
247258
x_measured = np.concatenate([q_meas, v_meas])
248259

249260
mpc.getDataHandler().updateInternalData(x_measured, True)
250261

251-
a_interp = (N_simu - j) / N_simu * a0 + j / N_simu * a1
252-
f_interp = (N_simu - j) / N_simu * forces0 + j / N_simu * forces1
253-
254262
qp.solveQP(
255263
mpc.getDataHandler().getData(),
256264
contact_states,
257265
x_measured[nq:],
258-
a_interp,
266+
interpolator.a_interpolated,
259267
np.zeros(12),
260-
f_interp,
268+
interpolator.forces_interpolated,
261269
mpc.getDataHandler().getData().M,
262270
)
263271

0 commit comments

Comments
 (0)