Skip to content

Commit

Permalink
dirty fix to Test compilation fail
Browse files Browse the repository at this point in the history
  • Loading branch information
mebbaid committed Jul 11, 2023
1 parent 230f1a4 commit 130056d
Show file tree
Hide file tree
Showing 5 changed files with 21 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
#include <string>
#include <vector>

#include <casadi/casadi.hpp>

#include <BipedalLocomotion/Contacts/Contact.h>
#include <BipedalLocomotion/Contacts/ContactPhaseList.h>
#include <BipedalLocomotion/ParametersHandler/IParametersHandler.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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:
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,7 @@ namespace ReducedModelControllers



class ParametrizedCentroidalMPC : public System::Source<ParametrizedCentroidalMPCState>
, public BaseCentroidalMPC
class ParametrizedCentroidalMPC : public BaseCentroidalMPC
{
public:

Expand All @@ -53,6 +52,8 @@ class ParametrizedCentroidalMPC : public System::Source<ParametrizedCentroidalMP

const ParametrizedCentroidalMPCState& getParametrizedOutput() const override;

const CentroidalMPCOutput& getOutput() const override;

bool isOutputValid() const override;

bool advance() override;
Expand Down
7 changes: 7 additions & 0 deletions src/ReducedModelControllers/src/CentroidalMPC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ struct CentroidalMPC::Impl
std::chrono::nanoseconds currentTime{std::chrono::nanoseconds::zero()};

CentroidalMPCOutput output;
ParametrizedCentroidalMPCState Invalidoutput;
Contacts::ContactPhaseList contactPhaseList;
Math::LinearizedFrictionCone frictionCone;

Expand Down Expand Up @@ -953,6 +954,12 @@ const CentroidalMPCOutput& CentroidalMPC::getOutput() const
return m_pimpl->output;
}

const ParametrizedCentroidalMPCState& CentroidalMPC::getParametrizedOutput() const
{
return m_pimpl->Invalidoutput;
}


bool CentroidalMPC::isOutputValid() const
{
return m_pimpl->fsm == Impl::FSM::OutputValid;
Expand Down
6 changes: 6 additions & 0 deletions src/ReducedModelControllers/src/ParametrizedCentroidalMPC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 130056d

Please sign in to comment.