From aa03967036475e705f2afa3e4b1d4a32d843ee6d Mon Sep 17 00:00:00 2001 From: Giulio Romualdi Date: Fri, 18 Sep 2020 10:13:43 +0200 Subject: [PATCH] Bugfix in TrajectoryGenerator::getIsStancePhase() method --- src/TrajectoryPlanner/src/TrajectoryGenerator.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/TrajectoryPlanner/src/TrajectoryGenerator.cpp b/src/TrajectoryPlanner/src/TrajectoryGenerator.cpp index 850e70f6..95221c5b 100644 --- a/src/TrajectoryPlanner/src/TrajectoryGenerator.cpp +++ b/src/TrajectoryPlanner/src/TrajectoryGenerator.cpp @@ -666,7 +666,9 @@ bool TrajectoryGenerator::getIsStancePhase(std::vector& 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)