diff --git a/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/BaseCentroidalMPC.h b/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/BaseCentroidalMPC.h index 7c94373292..e41ab0e6e6 100644 --- a/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/BaseCentroidalMPC.h +++ b/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/BaseCentroidalMPC.h @@ -13,6 +13,8 @@ #include #include +#include + #include #include #include diff --git a/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/CentroidalMPC.h b/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/CentroidalMPC.h index d41ab451a7..4615eea055 100644 --- a/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/CentroidalMPC.h +++ b/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/CentroidalMPC.h @@ -146,6 +146,8 @@ class CentroidalMPC : public BaseCentroidalMPC */ const CentroidalMPCOutput& getOutput() const override; + const ParametrizedCentroidalMPCState& getParametrizedOutput() const override; + /** * Determines the validity of the object retrieved with getOutput() * @return True if the object is valid, false otherwise. @@ -156,7 +158,7 @@ class CentroidalMPC : public BaseCentroidalMPC * Perform one control cycle. * @return True if the advance is successfull. */ - bool advance() override; + bool advance() override; private: /** diff --git a/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/ParametrizedCentroidalMPC.h b/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/ParametrizedCentroidalMPC.h index bf60e8c789..3c4112fb05 100644 --- a/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/ParametrizedCentroidalMPC.h +++ b/src/ReducedModelControllers/include/BipedalLocomotion/ReducedModelControllers/ParametrizedCentroidalMPC.h @@ -26,8 +26,7 @@ namespace ReducedModelControllers -class ParametrizedCentroidalMPC : public System::Source - , public BaseCentroidalMPC +class ParametrizedCentroidalMPC : public BaseCentroidalMPC { public: @@ -53,6 +52,8 @@ class ParametrizedCentroidalMPC : public System::Sourceoutput; } +const ParametrizedCentroidalMPCState& CentroidalMPC::getParametrizedOutput() const +{ + return m_pimpl->Invalidoutput; +} + + bool CentroidalMPC::isOutputValid() const { return m_pimpl->fsm == Impl::FSM::OutputValid; diff --git a/src/ReducedModelControllers/src/ParametrizedCentroidalMPC.cpp b/src/ReducedModelControllers/src/ParametrizedCentroidalMPC.cpp index 3ea027cf69..83911cdcd4 100644 --- a/src/ReducedModelControllers/src/ParametrizedCentroidalMPC.cpp +++ b/src/ReducedModelControllers/src/ParametrizedCentroidalMPC.cpp @@ -26,6 +26,7 @@ struct ParametrizedCentroidalMPC::Impl std::chrono::nanoseconds currentTime{std::chrono::nanoseconds::zero()}; ParametrizedCentroidalMPCState output; + CentroidalMPCOutput Invalidoutput; Contacts::ContactPhaseList contactPhaseList; enum class FSM @@ -1054,6 +1055,11 @@ const ParametrizedCentroidalMPCState& ParametrizedCentroidalMPC::getParametrized return m_pimpl->output; } +const CentroidalMPCOutput& ParametrizedCentroidalMPC::getOutput() const +{ + return m_pimpl->Invalidoutput; +} + bool ParametrizedCentroidalMPC::isOutputValid() const { return m_pimpl->fsm == Impl::FSM::OutputValid;