Skip to content

Commit 3214932

Browse files
authored
Merge pull request #43 from Simple-Robotics/topic/interpolate_state
Add interpolate state function
2 parents 6eacd83 + fb8b231 commit 3214932

File tree

5 files changed

+81
-6
lines changed

5 files changed

+81
-6
lines changed

bindings/expose-interpolate.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,15 @@ namespace simple_mpc
2626
return q_interp;
2727
}
2828

29+
Eigen::VectorXd interpolateStateProxy(
30+
Interpolator & self, const double delay, const double timestep, const std::vector<Eigen::VectorXd> & xs)
31+
{
32+
Eigen::VectorXd x_interp(xs[0].size());
33+
self.interpolateState(delay, timestep, xs, x_interp);
34+
35+
return x_interp;
36+
}
37+
2938
Eigen::VectorXd interpolateLinearProxy(
3039
Interpolator & self, const double delay, const double timestep, const std::vector<Eigen::VectorXd> & vs)
3140
{
@@ -39,6 +48,7 @@ namespace simple_mpc
3948
{
4049
bp::class_<Interpolator>("Interpolator", bp::init<const Model &>(bp::args("self", "model")))
4150
.def("interpolateConfiguration", &interpolateConfigurationProxy)
51+
.def("interpolateState", &interpolateStateProxy)
4252
.def("interpolateLinear", &interpolateLinearProxy);
4353
}
4454
} // namespace python

examples/go2_fulldynamics.py

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -249,8 +249,7 @@
249249

250250
forces = [total_forces, total_forces]
251251
ddqs = [a0, a1]
252-
qss = [mpc.xs[0][:model_handler.getModel().nq], mpc.xs[1][:model_handler.getModel().nq]]
253-
vss = [mpc.xs[0][model_handler.getModel().nq:], mpc.xs[1][model_handler.getModel().nq:]]
252+
xss = [mpc.xs[0], mpc.xs[1]]
254253
uss = [mpc.us[0], mpc.us[1]]
255254

256255
FL_measured.append(mpc.getDataHandler().getFootPose("FL_foot").translation)
@@ -269,14 +268,11 @@
269268
# time.sleep(0.01)
270269
delay = j / float(N_simu) * dt
271270

272-
q_interp = interpolator.interpolateConfiguration(delay, dt, qss)
273-
v_interp = interpolator.interpolateLinear(delay, dt, vss)
271+
x_interp = interpolator.interpolateState(delay, dt, xss)
274272
u_interp = interpolator.interpolateLinear(delay, dt, uss)
275273
acc_interp = interpolator.interpolateLinear(delay, dt, ddqs)
276274
force_interp = interpolator.interpolateLinear(delay, dt, forces)
277275

278-
x_interp = np.concatenate((q_interp, v_interp))
279-
280276
q_meas, v_meas = device.measureState()
281277
x_measured = np.concatenate([q_meas, v_meas])
282278

include/simple-mpc/interpolator.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,12 @@ namespace simple_mpc
3131
const std::vector<Eigen::VectorXd> & qs,
3232
Eigen::Ref<Eigen::VectorXd> q_interp);
3333

34+
void interpolateState(
35+
const double delay,
36+
const double timestep,
37+
const std::vector<Eigen::VectorXd> & xs,
38+
Eigen::Ref<Eigen::VectorXd> x_interp);
39+
3440
void interpolateLinear(
3541
const double delay,
3642
const double timestep,

src/interpolator.cpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,30 @@ namespace simple_mpc
3636
}
3737
}
3838

39+
void Interpolator::interpolateState(
40+
const double delay,
41+
const double timestep,
42+
const std::vector<Eigen::VectorXd> & xs,
43+
Eigen::Ref<Eigen::VectorXd> x_interp)
44+
{
45+
assert(("State is not of the right size", xs[0].size() == model_.nq + model_.nv));
46+
47+
// Compute the time knot corresponding to the current delay
48+
size_t step_nb = static_cast<size_t>(delay / timestep);
49+
double step_progress = (delay - (double)step_nb * timestep) / timestep;
50+
51+
// Interpolate state trajectory
52+
if (step_nb >= xs.size() - 1)
53+
x_interp = xs.back();
54+
else
55+
{
56+
x_interp.head(model_.nq) =
57+
pinocchio::interpolate(model_, xs[step_nb].head(model_.nq), xs[step_nb + 1].head(model_.nq), step_progress);
58+
x_interp.tail(model_.nv) =
59+
xs[step_nb + 1].tail(model_.nv) * step_progress + xs[step_nb].tail(model_.nv) * (1. - step_progress);
60+
}
61+
}
62+
3963
void Interpolator::interpolateLinear(
4064
const double delay,
4165
const double timestep,

tests/interpolator.cpp

Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,45 @@ BOOST_AUTO_TEST_CASE(interpolate)
6060
interpolator.interpolateConfiguration(delay, timestep, qs2, q_interp);
6161
BOOST_CHECK(qs2[0].isApprox(q_interp));
6262

63+
// Test state interpolation method
64+
std::vector<Eigen::VectorXd> xs;
65+
for (std::size_t i = 0; i < 4; i++)
66+
{
67+
Eigen::VectorXd x0(model.nq + model.nv);
68+
x0.head(model.nq) = pinocchio::neutral(model);
69+
Eigen::VectorXd dq(model.nv);
70+
dq.setRandom();
71+
pinocchio::integrate(model, x0.head(model.nq), dq, x0.head(model.nq));
72+
x0.tail(model.nv).setRandom();
73+
74+
xs.push_back(x0);
75+
}
76+
delay = 0.02;
77+
78+
Eigen::VectorXd x_interp(model.nq + model.nv);
79+
interpolator.interpolateState(delay, timestep, xs, x_interp);
80+
BOOST_CHECK(xs[2].isApprox(x_interp));
81+
82+
delay = 0.5;
83+
interpolator.interpolateState(delay, timestep, xs, x_interp);
84+
BOOST_CHECK(xs.back().isApprox(x_interp));
85+
86+
delay = 0.005;
87+
interpolator.interpolateState(delay, timestep, xs, x_interp);
88+
Eigen::VectorXd x_interp2(model.nq + model.nv);
89+
pinocchio::difference(model, xs[0].head(model.nq), xs[1].head(model.nq), dq);
90+
pinocchio::integrate(model, xs[0].head(model.nq), dq * 0.5, x_interp2.head(model.nq));
91+
x_interp2.tail(model.nv) = (xs[0].tail(model.nv) + xs[1].tail(model.nv)) * 0.5;
92+
BOOST_CHECK(x_interp2.isApprox(x_interp));
93+
94+
std::vector<Eigen::VectorXd> xs2;
95+
for (std::size_t i = 0; i < 2; i++)
96+
{
97+
xs2.push_back(xs[0]);
98+
}
99+
interpolator.interpolateState(delay, timestep, xs2, x_interp);
100+
BOOST_CHECK(xs2[0].isApprox(x_interp));
101+
63102
// Test linear interpolation method
64103
std::vector<Eigen::VectorXd> vs;
65104
for (std::size_t i = 0; i < 4; i++)

0 commit comments

Comments
 (0)