Skip to content

Commit

Permalink
Bugfix in TrajectoryGenerator::getIsStancePhase() method
Browse files Browse the repository at this point in the history
  • Loading branch information
GiulioRomualdi committed Sep 18, 2020
1 parent 9963563 commit aa03967
Showing 1 changed file with 3 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

0 comments on commit aa03967

Please sign in to comment.