Skip to content

Commit

Permalink
Merge pull request #68 from GiulioRomualdi/fix/is_stance_phase
Browse files Browse the repository at this point in the history
Fix the stance phase machinery
  • Loading branch information
S-Dafarra authored Sep 18, 2020
2 parents 9963563 + 578f87d commit 33e9b06
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 1 deletion.
4 changes: 3 additions & 1 deletion src/TrajectoryPlanner/src/TrajectoryGenerator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -666,7 +666,9 @@ bool TrajectoryGenerator::getIsStancePhase(std::vector<bool>& isStancePhase)
{
// decreased the counter only if it is different from zero.
// it is required to add a delay in the beginning of the stance phase
stancePhaseDelayCounter = stancePhaseDelayCounter == 0 ? 0 : stancePhaseDelayCounter--;
stancePhaseDelayCounter = (stancePhaseDelayCounter == 0)
? 0
: (stancePhaseDelayCounter - 1);

// the delay expired the robot can be considered stance
if(stancePhaseDelayCounter == 0)
Expand Down
3 changes: 3 additions & 0 deletions src/WalkingModule/src/Module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,9 @@ bool WalkingModule::advanceReferenceSignals()
m_comHeightVelocity.pop_front();
m_comHeightVelocity.push_back(m_comHeightVelocity.back());

m_isStancePhase.pop_front();
m_isStancePhase.push_back(m_isStancePhase.back());

// at each sampling time the merge points are decreased by one.
// If the first merge point is equal to 0 it will be dropped.
// A new trajectory will be merged at the first merge point or if the deque is empty
Expand Down

0 comments on commit 33e9b06

Please sign in to comment.