Skip to content

Commit

Permalink
update bindings centroidal MPC
Browse files Browse the repository at this point in the history
  • Loading branch information
CarlottaSartore committed Jun 28, 2023
1 parent fc5d968 commit a8d6a8c
Showing 1 changed file with 12 additions and 14 deletions.
26 changes: 12 additions & 14 deletions bindings/python/ReducedModelControllers/src/CentroidalMPC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,32 +26,30 @@ void CreateCentroidalMPC(pybind11::module& module)
using namespace BipedalLocomotion::ReducedModelControllers;
using namespace BipedalLocomotion::System;

py::class_<CentroidalMPCState>(module, "CentroidalMPCState")
py::class_<CentroidalMPCOutput>(module, "CentroidalMPCState")
.def(py::init())
.def_readwrite("contacts", &CentroidalMPCState::contacts)
.def_readwrite("next_planned_contact", &CentroidalMPCState::nextPlannedContact)
.def_readwrite("computational_time", &CentroidalMPCState::computationalTime)
.def_readwrite("external_wrench",&CentroidalMPCState::externalWrench);
.def_readwrite("contacts", &CentroidalMPCOutput::contacts)
.def_readwrite("next_planned_contact", &CentroidalMPCOutput::nextPlannedContact);

BipedalLocomotion::bindings::System::CreateSource<CentroidalMPCState>(module,
"CentroidalMPCState");
py::class_<CentroidalMPC, Source<CentroidalMPCState>>(module, "CentroidalMPC")
BipedalLocomotion::bindings::System::CreateSource<CentroidalMPCOutput>(module,
"CentroidalMPCOutput");
py::class_<CentroidalMPC, Source<CentroidalMPCOutput>>(module, "CentroidalMPC")
.def(py::init())
.def("initialize", [](CentroidalMPC& impl,
std::shared_ptr<const BipedalLocomotion::ParametersHandler::IParametersHandler>
handler) -> bool { return impl.initialize(handler);},
py::arg("handler"))
.def("set_contact_phase_list", py::overload_cast<const Contacts::ContactPhaseList&>(&CentroidalMPC::setContactPhaseList),
py::arg("contactPhaseList") )
.def("set_state", py::overload_cast<Eigen::Ref<const Eigen::Vector3d>,Eigen::Ref<const Eigen::Vector3d>,Eigen::Ref<const Eigen::Vector3d>,std::optional<Eigen::Ref<const Eigen::Vector3d>>>(&CentroidalMPC::setState),
.def("set_state", py::overload_cast<Eigen::Ref<const Eigen::Vector3d>,Eigen::Ref<const Eigen::Vector3d>,Eigen::Ref<const Eigen::Vector3d>>(&CentroidalMPC::setState),
py::arg("com"),
py::arg("dcom"),
py::arg("angularMomentum"),
py::arg("externalWrench"))
.def("set_reference_trajectory", py::overload_cast<Eigen::Ref<const Eigen::MatrixXd>>(&CentroidalMPC::setReferenceTrajectory),
py::arg("com"))
py::arg("angularMomentum"))
.def("set_reference_trajectory", py::overload_cast<const std::vector<Eigen::Vector3d>&,const std::vector<Eigen::Vector3d>&>(&CentroidalMPC::setReferenceTrajectory),
py::arg("com"),
py::arg("angularMomentum"))
.def("get_output",
[](const CentroidalMPC& l) -> const CentroidalMPCState& {
[](const CentroidalMPC& l) -> const CentroidalMPCOutput& {
return l.getOutput();
})
.def("is_output_valid", &CentroidalMPC::isOutputValid)
Expand Down

0 comments on commit a8d6a8c

Please sign in to comment.