Skip to content

Commit

Permalink
Avoid to print continuosly the warning about the timings
Browse files Browse the repository at this point in the history
  • Loading branch information
S-Dafarra committed May 24, 2024
1 parent f0a996b commit c5e1e5d
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 5 deletions.
2 changes: 2 additions & 0 deletions include/DCMTrajectoryGeneratorHelper.h
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,8 @@ class DCMTrajectoryGeneratorHelper
std::vector<iDynTree::Vector2> m_ZMPPosition; /**< Vector containing the position of the ZMP. */
std::vector<double> m_weightInLeft, m_weightInRight; /**< Vectors containing the percentage of weight carried by the foot. */

bool m_timingWarningPrinted{false}; /**< Flag used to print a warning message about the timings only once. */


/**
* Add the last Single and Double support phases.
Expand Down
12 changes: 9 additions & 3 deletions src/DCMTrajectoryGeneratorHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1467,9 +1467,15 @@ bool DCMTrajectoryGeneratorHelper::setPauseConditions(bool pauseActive, const do
return false;
}

if (nominalDoubleSupportDuration + endSwitchTime > maxDoubleSupportDuration){
std::cerr << "[DCMTrajectoryGeneratorHelper::setPauseConditions] Warning: the sum of nominalDoubleSupportDuration and endSwitchTime is greater than maxDoubleSupportDuration. ";
std::cerr << "The robot might not be able to pause in the middle of the stance phase." << std::endl;
if (nominalDoubleSupportDuration + endSwitchTime > maxDoubleSupportDuration) {
if (!m_timingWarningPrinted) {
std::cerr << "[DCMTrajectoryGeneratorHelper::setPauseConditions] Warning: the sum of nominalDoubleSupportDuration and endSwitchTime is greater than maxDoubleSupportDuration. ";
std::cerr << "The robot might not be able to pause in the middle of the stance phase." << std::endl;
m_timingWarningPrinted = true;
}
}
else {
m_timingWarningPrinted = false;
}
}
m_nominalDoubleSupportDuration = nominalDoubleSupportDuration;
Expand Down
11 changes: 9 additions & 2 deletions src/ZMPTrajectoryGenerator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ class ZMPTrajectoryGenerator::ZMPTrajectoryGeneratorImplementation {
std::vector<iDynTree::Vector2> leftZMPAcceleration, rightZMPAcceleration, worldZMPAcceleration;

bool initialWeightSpecified = false, previousStepsSpecified = false;
bool timingWarningPrinted = false;

std::mutex mutex;

Expand Down Expand Up @@ -519,8 +520,14 @@ bool ZMPTrajectoryGenerator::computeNewTrajectories(double initTime, double dT,
m_pimpl->endSwitchTime = endSwitchTime;

if (m_pimpl->nominalSwitchTime + endSwitchTime > m_pimpl->maxSwitchTime) {
std::cerr << "[ZMPTrajectoryGenerator::computeNewTrajectories] Warning: the sum of nominalSwitchTime and endSwitchTime is greater than maxSwitchTime. ";
std::cerr << "The robot might not be able to pause in the middle of the stance phase." << std::endl;
if (!m_pimpl->timingWarningPrinted) {
std::cerr << "[ZMPTrajectoryGenerator::computeNewTrajectories] Warning: the sum of nominalSwitchTime and endSwitchTime is greater than maxSwitchTime. ";
std::cerr << "The robot might not be able to pause in the middle of the stance phase." << std::endl;
m_pimpl->timingWarningPrinted = true;
}
}
else {
m_pimpl->timingWarningPrinted = false;
}

if (!(m_pimpl->initialWeightSpecified)) {
Expand Down

0 comments on commit c5e1e5d

Please sign in to comment.