Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix the stance phase machinery #68

Merged
merged 2 commits into from
Sep 18, 2020
Merged
Show file tree
Hide file tree
Changes from all 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
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