Skip to content

Commit f9e8af7

Browse files
authored
Merge pull request #45 from Simple-Robotics/topic/get_force
Add get force function to extract forces from fulldynamics MPC
2 parents 8611a62 + 64c0e86 commit f9e8af7

File tree

5 files changed

+59
-16
lines changed

5 files changed

+59
-16
lines changed

bindings/expose-mpc.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,7 @@ namespace simple_mpc
8888
.def("getFootTakeoffCycle", &MPC::getFootTakeoffCycle, ("self"_a, "ee_name"))
8989
.def("getFootLandCycle", &MPC::getFootLandCycle, ("self"_a, "ee_name"))
9090
.def("getStateDerivative", &MPC::getStateDerivative, ("self"_a, "t"))
91+
.def("getContactForces", &MPC::getContactForces, ("self"_a, "t"))
9192
.def("getCyclingContactState", &MPC::getCyclingContactState, ("self"_a, "t", "ee_name"))
9293
.def(
9394
"getModelHandler", &MPC::getModelHandler, "self"_a, bp::return_internal_reference<>(),

examples/go2_fulldynamics.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -201,7 +201,7 @@
201201
L_measured = []
202202

203203
v = np.zeros(6)
204-
v[0] = 0.
204+
v[0] = 0.2
205205
mpc.velocity_base = v
206206
for t in range(500):
207207
print("Time " + str(t))
@@ -214,7 +214,6 @@
214214
str(land_RF) + ", takeoff_LF = " + str(takeoff_LF) + ", landing_LF = ",
215215
str(land_LF),
216216
) """
217-
218217
""" if t == 200:
219218
for s in range(T):
220219
device.resetState(mpc.xs[s][:nq])
@@ -238,15 +237,16 @@
238237
a0 = mpc.getStateDerivative(0)[nv:]
239238
a1 = mpc.getStateDerivative(1)[nv:]
240239

241-
FL_f, FR_f, RL_f, RR_f = extract_forces(mpc.getTrajOptProblem(), mpc.solver.workspace, 0)
240+
forces_vec0 = mpc.getContactForces(0)
241+
forces_vec1 = mpc.getContactForces(1)
242242
contact_states = mpc.ocp_handler.getContactState(0)
243-
total_forces = np.concatenate((FL_f, FR_f, RL_f, RR_f))
244-
force_FL.append(FL_f)
245-
force_FR.append(FR_f)
246-
force_RL.append(RL_f)
247-
force_RR.append(RR_f)
248243

249-
forces = [total_forces, total_forces]
244+
force_FL.append(forces_vec0[:3])
245+
force_FR.append(forces_vec0[3:6])
246+
force_RL.append(forces_vec0[6:9])
247+
force_RR.append(forces_vec0[9:12])
248+
249+
forces = [forces_vec0, forces_vec1]
250250
ddqs = [a0, a1]
251251
xss = [mpc.xs[0], mpc.xs[1]]
252252
uss = [mpc.us[0], mpc.us[1]]

include/simple-mpc/mpc.hpp

Lines changed: 10 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
#include <aligator/fwd.hpp>
1212
#include <aligator/modelling/dynamics/fwd.hpp>
1313
#include <aligator/modelling/dynamics/integrator-explicit.hpp>
14+
#include <aligator/modelling/dynamics/multibody-constraint-fwd.hpp>
1415
#include <aligator/solvers/proxddp/solver-proxddp.hpp>
1516

1617
#include "simple-mpc/deprecated.hpp"
@@ -22,6 +23,8 @@
2223
namespace simple_mpc
2324
{
2425
using ExplicitIntegratorData = dynamics::ExplicitIntegratorDataTpl<double>;
26+
using MultibodyConstraintFwdData = dynamics::MultibodyConstraintFwdDataTpl<double>;
27+
using MultibodyConstraintFwdDynamics = dynamics::MultibodyConstraintFwdDynamicsTpl<double>;
2528

2629
struct MPCSettings
2730
{
@@ -175,13 +178,13 @@ namespace simple_mpc
175178
}
176179
}
177180

178-
const ConstVectorRef getStateDerivative(const std::size_t t)
179-
{
180-
ExplicitIntegratorData * int_data =
181-
dynamic_cast<ExplicitIntegratorData *>(&*solver_->workspace_.problem_data.stage_data[t]->dynamics_data);
182-
assert(int_data != nullptr);
183-
return int_data->continuous_data->xdot_;
184-
}
181+
const ConstVectorRef getStateDerivative(const std::size_t t);
182+
183+
/**
184+
* @brief Return contact forces for a full dynamics MPC problem
185+
* @warning Only work with fulldynamics OCP handler
186+
*/
187+
const Eigen::VectorXd getContactForces(const std::size_t t);
185188

186189
void switchToWalk(const Vector6d & velocity_base);
187190

src/mpc.cpp

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -342,6 +342,43 @@ namespace simple_mpc
342342
return ocp_handler_->getProblem();
343343
}
344344

345+
const ConstVectorRef MPC::getStateDerivative(const std::size_t t)
346+
{
347+
ExplicitIntegratorData * int_data =
348+
dynamic_cast<ExplicitIntegratorData *>(&*solver_->workspace_.problem_data.stage_data[t]->dynamics_data);
349+
assert(int_data != nullptr);
350+
return int_data->continuous_data->xdot_;
351+
}
352+
353+
const Eigen::VectorXd MPC::getContactForces(const std::size_t t)
354+
{
355+
Eigen::VectorXd contact_forces;
356+
contact_forces.resize(3 * (long)ee_names_.size());
357+
358+
ExplicitIntegratorData * int_data =
359+
dynamic_cast<ExplicitIntegratorData *>(&*solver_->workspace_.problem_data.stage_data[t]->dynamics_data);
360+
assert(int_data != nullptr);
361+
MultibodyConstraintFwdData * mc_data = dynamic_cast<MultibodyConstraintFwdData *>(&*int_data->continuous_data);
362+
assert(mc_data != nullptr);
363+
364+
std::vector<bool> contact_state = ocp_handler_->getContactState(t);
365+
366+
size_t force_id = 0;
367+
for (size_t i = 0; i < contact_state.size(); i++)
368+
{
369+
if (contact_state[i])
370+
{
371+
contact_forces.segment((long)i * 3, 3) = mc_data->constraint_datas_[force_id].contact_force.linear();
372+
force_id += 1;
373+
}
374+
else
375+
{
376+
contact_forces.segment((long)i * 3, 3).setZero();
377+
}
378+
}
379+
return contact_forces;
380+
}
381+
345382
void MPC::switchToWalk(const Vector6d & velocity_base)
346383
{
347384
now_ = WALKING;

tests/mpc.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,8 @@ BOOST_AUTO_TEST_CASE(mpc_fulldynamics)
9090
BOOST_CHECK_EQUAL(mpc.foot_land_times_.at("right_sole_link")[0], 150);
9191

9292
Eigen::VectorXd xdot = mpc.getStateDerivative(0);
93+
94+
Eigen::VectorXd forces = mpc.getContactForces(0);
9395
}
9496

9597
BOOST_AUTO_TEST_CASE(mpc_kinodynamics)

0 commit comments

Comments
 (0)