Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions bindings/expose-mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@ namespace simple_mpc
.def("switchToStand", &MPC::switchToStand, "self"_a)
.def("getFootTakeoffCycle", &MPC::getFootTakeoffCycle, ("self"_a, "ee_name"))
.def("getFootLandCycle", &MPC::getFootLandCycle, ("self"_a, "ee_name"))
.def("getStateDerivative", &MPC::getStateDerivative, ("self"_a, "t"))
.def("getCyclingContactState", &MPC::getCyclingContactState, ("self"_a, "t", "ee_name"))
.def(
"getModelHandler", &MPC::getModelHandler, "self"_a, bp::return_internal_reference<>(),
Expand Down
1 change: 1 addition & 0 deletions bindings/expose-problem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ namespace simple_mpc
.def("getPoseBase", bp::pure_virtual(&OCPHandler::getPoseBase), bp::args("self", "t"))
.def("getProblemState", bp::pure_virtual(&OCPHandler::getProblemState), bp::args("self", "data_handler"))
.def("getContactSupport", bp::pure_virtual(&OCPHandler::getContactSupport), bp::args("self", "t"))
.def("getContactState", bp::pure_virtual(&OCPHandler::getContactState), bp::args("self", "t"))
.def(
"createProblem", &OCPHandler::createProblem,
("self"_a, "x0", "horizon", "force_size", "gravity", "terminal_constraint"))
Expand Down
15 changes: 4 additions & 11 deletions examples/go2_fulldynamics.py
Original file line number Diff line number Diff line change
Expand Up @@ -221,18 +221,11 @@
end = time.time()
solve_time.append(end - start)

a0 = (
mpc.solver
.workspace.problem_data.stage_data[0]
.dynamics_data.continuous_data.xdot[nv:]
)
a1 = (
mpc.solver
.workspace.problem_data.stage_data[1]
.dynamics_data.continuous_data.xdot[nv:]
)
a0 = mpc.getStateDerivative(0)[nv:]
a1 = mpc.getStateDerivative(1)[nv:]

FL_f, FR_f, RL_f, RR_f, contact_states = extract_forces(mpc.getTrajOptProblem(), mpc.solver.workspace, 0)
FL_f, FR_f, RL_f, RR_f = extract_forces(mpc.getTrajOptProblem(), mpc.solver.workspace, 0)
contact_states = mpc.ocp_handler.getContactState(0)
total_forces = np.concatenate((FL_f, FR_f, RL_f, RR_f))
force_FL.append(FL_f)
force_FR.append(FR_f)
Expand Down
17 changes: 4 additions & 13 deletions examples/go2_kinodynamics.py
Original file line number Diff line number Diff line change
Expand Up @@ -225,23 +225,14 @@
com_measured.append(mpc.getDataHandler().getData().com[0].copy())
L_measured.append(mpc.getDataHandler().getData().hg.angular.copy())

a0 = (
mpc.solver
.workspace.problem_data.stage_data[0]
.dynamics_data.continuous_data.xdot[nv:]
)
a1 = (
mpc.solver
.workspace.problem_data.stage_data[1]
.dynamics_data.continuous_data.xdot[nv:]
)
a0 = mpc.getStateDerivative(0)[nv:]
a1 = mpc.getStateDerivative(1)[nv:]

a0[6:] = mpc.us[0][nk * force_size :]
a1[6:] = mpc.us[1][nk * force_size :]
forces0 = mpc.us[0][: nk * force_size]
forces1 = mpc.us[1][: nk * force_size]
contact_states = (
mpc.getTrajOptProblem().stages[0].dynamics.differential_dynamics.contact_states
)
contact_states = mpc.ocp_handler.getContactState(0)

device.moveQuadrupedFeet(
mpc.getReferencePose(0, "FL_foot").translation,
Expand Down
12 changes: 2 additions & 10 deletions examples/talos_centroidal.py
Original file line number Diff line number Diff line change
Expand Up @@ -201,18 +201,10 @@
mpc.getReferencePose(0, "right_sole_link").translation,
)

contact_states = (
mpc.getTrajOptProblem()
.stages[0]
.dynamics.differential_dynamics.contact_map.contact_states.tolist()
)
contact_states = mpc.ocp_handler.getContactState(0)
foot_ref = [mpc.getReferencePose(0, name) for name in model_handler.getFeetNames()]
foot_ref_next = [mpc.getReferencePose(1, name) for name in model_handler.getFeetNames()]
dH = (
mpc.solver
.workspace.problem_data.stage_data[0]
.dynamics_data.continuous_data.xdot[3:9]
)
dH = mpc.getStateDerivative(0)[3:9]
qp.computeDifferences(
mpc.getDataHandler().getData(), x_measured, foot_ref, foot_ref_next
)
Expand Down
17 changes: 4 additions & 13 deletions examples/talos_kinodynamics.py
Original file line number Diff line number Diff line change
Expand Up @@ -210,23 +210,14 @@
mpc.iterate(x_measured)
end = time.time()
print("MPC iterate = " + str(end - start))
a0 = (
mpc.solver
.workspace.problem_data.stage_data[0]
.dynamics_data.continuous_data.xdot[nv:]
)
a1 = (
mpc.solver
.workspace.problem_data.stage_data[1]
.dynamics_data.continuous_data.xdot[nv:]
)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

oh my god it was so long


a0 = mpc.getStateDerivative(0)[nv:]
a1 = mpc.getStateDerivative(1)[nv:]
a0[6:] = mpc.us[0][nk * force_size :]
a1[6:] = mpc.us[1][nk * force_size :]
forces0 = mpc.us[0][: nk * force_size]
forces1 = mpc.us[1][: nk * force_size]
contact_states = (
mpc.getTrajOptProblem().stages[0].dynamics.differential_dynamics.contact_states
)
contact_states = mpc.ocp_handler.getContactState(0)

device.moveMarkers(
mpc.getReferencePose(0, "left_sole_link").translation,
Expand Down
8 changes: 1 addition & 7 deletions examples/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,21 +71,15 @@ def extract_forces(problem, workspace, id):
force_FR = np.zeros(3)
force_RL = np.zeros(3)
force_RR = np.zeros(3)
contact_states = [False, False, False, False]
in_contact = problem.stages[id].dynamics.differential_dynamics.constraint_models.__len__()

for i in range(in_contact):
if problem.stages[id].dynamics.differential_dynamics.constraint_models[i].name == 'FL_foot':
contact_states[0] = True
force_FL = workspace.problem_data.stage_data[id].dynamics_data.continuous_data.constraint_datas[i].contact_force.linear
elif problem.stages[id].dynamics.differential_dynamics.constraint_models[i].name == 'FR_foot':
contact_states[1] = True
force_FR = workspace.problem_data.stage_data[id].dynamics_data.continuous_data.constraint_datas[i].contact_force.linear
elif problem.stages[id].dynamics.differential_dynamics.constraint_models[i].name == 'RL_foot':
contact_states[2] = True
force_RL = workspace.problem_data.stage_data[id].dynamics_data.continuous_data.constraint_datas[i].contact_force.linear
elif problem.stages[id].dynamics.differential_dynamics.constraint_models[i].name == 'RR_foot':
contact_states[3] = True
force_RR = workspace.problem_data.stage_data[id].dynamics_data.continuous_data.constraint_datas[i].contact_force.linear

return force_FL, force_FR, force_RL, force_RR, contact_states
return force_FL, force_FR, force_RL, force_RR
1 change: 1 addition & 0 deletions include/simple-mpc/centroidal-dynamics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ namespace simple_mpc
void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) override;
const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) override;
size_t getContactSupport(const std::size_t t) override;
std::vector<bool> getContactState(const std::size_t t) override;

CentroidalSettings getSettings()
{
Expand Down
1 change: 1 addition & 0 deletions include/simple-mpc/fulldynamics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,7 @@ namespace simple_mpc
void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) override;
const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) override;
size_t getContactSupport(const std::size_t t) override;
std::vector<bool> getContactState(const std::size_t t) override;
FullDynamicsSettings getSettings()
{
return settings_;
Expand Down
1 change: 1 addition & 0 deletions include/simple-mpc/kinodynamics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ namespace simple_mpc
void setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base) override;
const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) override;
size_t getContactSupport(const std::size_t t) override;
std::vector<bool> getContactState(const std::size_t t) override;

void computeControlFromForces(const std::map<std::string, Eigen::VectorXd> & force_refs);

Expand Down
12 changes: 12 additions & 0 deletions include/simple-mpc/mpc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
///////////////////////////////////////////////////////////////////////////////
#pragma once

#include <aligator/core/stage-data.hpp>
#include <aligator/fwd.hpp>
#include <aligator/modelling/dynamics/fwd.hpp>
#include <aligator/modelling/dynamics/integrator-explicit.hpp>
#include <aligator/solvers/proxddp/solver-proxddp.hpp>

#include "simple-mpc/deprecated.hpp"
Expand All @@ -17,6 +21,7 @@

namespace simple_mpc
{
using ExplicitIntegratorData = dynamics::ExplicitIntegratorDataTpl<double>;

struct MPCSettings
{
Expand Down Expand Up @@ -171,6 +176,13 @@ namespace simple_mpc
}
}

const Eigen::VectorXd getStateDerivative(const std::size_t t)
{
ExplicitIntegratorData * int_data =
dynamic_cast<ExplicitIntegratorData *>(&*solver_->workspace_.problem_data.stage_data[t]->dynamics_data);
return int_data->continuous_data->xdot_;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please return ConstVectorRef to get a numpy view array in Python (that you can explicitly copy). This avoids doing copies when not needed.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also add an assert() or other runtime check that int_data is not nullptr - which would be a cast error.

}

void switchToWalk(const Vector6d & velocity_base);

void switchToStand();
Expand Down
1 change: 1 addition & 0 deletions include/simple-mpc/ocp-handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ namespace simple_mpc
virtual const Eigen::VectorXd getReferenceForce(const std::size_t t, const std::string & ee_name) = 0;
virtual const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) = 0;
virtual size_t getContactSupport(const std::size_t t) = 0;
virtual std::vector<bool> getContactState(const std::size_t t) = 0;

/// Common functions for all problems

Expand Down
5 changes: 5 additions & 0 deletions include/simple-mpc/python/py-ocp-handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,6 +165,11 @@ namespace simple_mpc
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(std::size_t, "getContactSupport", t);
}

std::vector<bool> getContactState(const std::size_t t) override
{
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(std::vector<bool>, "getContactState", t);
}

void setReferenceControl(const std::size_t t, const ConstVectorRef & u_ref)
{
SIMPLE_MPC_PYTHON_OVERRIDE(void, OCPHandler, setReferenceControl, t, u_ref);
Expand Down
12 changes: 12 additions & 0 deletions src/centroidal-dynamics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,6 +278,18 @@ namespace simple_mpc
return active_contacts;
}

std::vector<bool> CentroidalOCP::getContactState(const std::size_t t)
{
std::vector<bool> contact_state;
CentroidalFwdDynamics * ode =
problem_->stages_[t]->getDynamics<IntegratorEuler>()->getDynamics<CentroidalFwdDynamics>();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here also add a runtime check that ode is not nullptr.


for (auto name : model_handler_.getFeetNames())
contact_state.push_back(ode->contact_map_.getContactState(name));

return contact_state;
}

CostStack CentroidalOCP::createTerminalCost()
{
auto ter_space = VectorSpace(nx_);
Expand Down
25 changes: 25 additions & 0 deletions src/fulldynamics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -373,6 +373,31 @@ namespace simple_mpc
return ode->constraint_models_.size();
}

std::vector<bool> FullDynamicsOCP::getContactState(const std::size_t t)
{
std::vector<bool> contact_state;
MultibodyConstraintFwdDynamics * ode =
problem_->stages_[t]->getDynamics<IntegratorSemiImplEuler>()->getDynamics<MultibodyConstraintFwdDynamics>();

for (auto name : model_handler_.getFeetNames())
{
std::size_t i;
for (i = 0; i < ode->constraint_models_.size(); i++)
{
if (ode->constraint_models_[i].name == name)
{
contact_state.push_back(true);
break;
}
}
if (i == ode->constraint_models_.size())
{
contact_state.push_back(false);
}
}
return contact_state;
}

CostStack FullDynamicsOCP::createTerminalCost()
{
auto ter_space = MultibodyPhaseSpace(model_handler_.getModel());
Expand Down
8 changes: 8 additions & 0 deletions src/kinodynamics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -322,6 +322,14 @@ namespace simple_mpc
return active_contacts;
}

std::vector<bool> KinodynamicsOCP::getContactState(const std::size_t t)
{
KinodynamicsFwdDynamics * ode =
problem_->stages_[t]->getDynamics<IntegratorSemiImplEuler>()->getDynamics<KinodynamicsFwdDynamics>();

return ode->contact_states_;
}

CostStack KinodynamicsOCP::createTerminalCost()
{
auto ter_space = MultibodyPhaseSpace(model_handler_.getModel());
Expand Down
6 changes: 6 additions & 0 deletions tests/mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,8 @@ BOOST_AUTO_TEST_CASE(mpc_fulldynamics)
BOOST_CHECK_EQUAL(mpc.foot_takeoff_times_.at("right_sole_link")[0], 100);
BOOST_CHECK_EQUAL(mpc.foot_land_times_.at("left_sole_link")[0], 209);
BOOST_CHECK_EQUAL(mpc.foot_land_times_.at("right_sole_link")[0], 150);

Eigen::VectorXd xdot = mpc.getStateDerivative(0);
}

BOOST_AUTO_TEST_CASE(mpc_kinodynamics)
Expand Down Expand Up @@ -161,6 +163,8 @@ BOOST_AUTO_TEST_CASE(mpc_kinodynamics)
{
mpc.iterate(model_handler.getReferenceState());
}

Eigen::VectorXd xdot = mpc.getStateDerivative(0);
}

BOOST_AUTO_TEST_CASE(mpc_centroidal)
Expand Down Expand Up @@ -236,6 +240,8 @@ BOOST_AUTO_TEST_CASE(mpc_centroidal)
{
mpc.iterate(x_multibody);
}

Eigen::VectorXd xdot = mpc.getStateDerivative(0);
}

BOOST_AUTO_TEST_SUITE_END()
8 changes: 8 additions & 0 deletions tests/problem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,10 @@ BOOST_AUTO_TEST_CASE(fulldynamics)
QuadraticResidualCost * crc = csp->getComponent<QuadraticResidualCost>("centroidal_cost");
QuadraticResidualCost * cpc = csp->getComponent<QuadraticResidualCost>("left_sole_link_pose_cost");

std::vector<bool> cs2 = {true, true};
BOOST_CHECK_EQUAL(fdproblem.getSize(), 100);
BOOST_CHECK_EQUAL(fdproblem.getContactSupport(2), 2);
BOOST_TEST(fdproblem.getContactState(2) == cs2);
BOOST_CHECK_EQUAL(cc->weights_, settings.w_u);
BOOST_CHECK_EQUAL(crc->weights_, settings.w_cent);
BOOST_CHECK_EQUAL(cpc->weights_, settings.w_frame);
Expand Down Expand Up @@ -137,7 +139,9 @@ BOOST_AUTO_TEST_CASE(kinodynamics)
QuadraticResidualCost * crc = csp->getComponent<QuadraticResidualCost>("centroidal_cost");
QuadraticResidualCost * cpc = csp->getComponent<QuadraticResidualCost>("left_sole_link_pose_cost");

std::vector<bool> cs2 = {true, true};
BOOST_CHECK_EQUAL(knproblem.getContactSupport(2), 2);
BOOST_TEST(knproblem.getContactState(2) == cs2);
BOOST_CHECK_EQUAL(cc->weights_, settings.w_u);
BOOST_CHECK_EQUAL(crc->weights_, settings.w_cent);
BOOST_CHECK_EQUAL(cpc->weights_, settings.w_frame);
Expand Down Expand Up @@ -220,7 +224,9 @@ BOOST_AUTO_TEST_CASE(centroidal)
QuadraticResidualCost * crc = csp->getComponent<QuadraticResidualCost>("linear_mom_cost");
QuadraticResidualCost * cpc = csp->getComponent<QuadraticResidualCost>("angular_acc_cost");

std::vector<bool> cs2 = {true, true};
BOOST_CHECK_EQUAL(cproblem.getContactSupport(2), 2);
BOOST_TEST(cproblem.getContactState(2) == cs2);
BOOST_CHECK_EQUAL(cc->weights_, settings.w_u);
BOOST_CHECK_EQUAL(crc->weights_, settings.w_linear_mom);
BOOST_CHECK_EQUAL(cpc->weights_, settings.w_angular_acc);
Expand Down Expand Up @@ -308,7 +314,9 @@ BOOST_AUTO_TEST_CASE(centroidal_solo)
QuadraticResidualCost * crc = csp->getComponent<QuadraticResidualCost>("linear_mom_cost");
QuadraticResidualCost * cpc = csp->getComponent<QuadraticResidualCost>("angular_acc_cost");

std::vector<bool> cs2 = {true, true, true, true};
BOOST_CHECK_EQUAL(cproblem.getContactSupport(2), 4);
BOOST_TEST(cproblem.getContactState(2) == cs2);
BOOST_CHECK_EQUAL(cc->weights_, settings.w_u);
BOOST_CHECK_EQUAL(crc->weights_, settings.w_linear_mom);
BOOST_CHECK_EQUAL(cpc->weights_, settings.w_angular_acc);
Expand Down
Loading