26 #include <VirtualRobot/MathTools.h>
30 #include <RobotAPI/interface/core/RobotState.h>
33 #include <VirtualRobot/Robot.h>
34 #include <VirtualRobot/Nodes/RobotNode.h>
35 #include <VirtualRobot/KinematicChain.h>
36 #include <VirtualRobot/Import/RobotImporterFactory.h>
37 #include <VirtualRobot/RuntimeEnvironment.h>
47 usingProxy(getProperty<std::string>(
"LongtermMemoryName").getValue());
48 usingProxy(getProperty<std::string>(
"RobotStateComponentName").getValue());
54 this->longtermMemoryPrx = getProxy<memoryx::LongtermMemoryInterfacePrx>(getProperty<std::string>(
"LongtermMemoryName").getValue());
55 this->robotStateComponentPrx = getProxy<armarx::RobotStateComponentInterfacePrx>(getProperty<std::string>(
"RobotStateComponentName").getValue());
83 const std::vector<memoryx::KBM::Real>& position)
85 VR_ASSERT_MESSAGE((
int)(position.size()) == kbm.
getNDim(),
"position size doesn't match KBM dimensions");
86 return Eigen::Map<const memoryx::KBM::Vector>(position.data(), kbm.
getNDim());
90 const std::vector<memoryx::KBM::Real>& proprioception)
92 VR_ASSERT_MESSAGE((
int)(proprioception.size()) == kbm.
getNDoF(),
"proprioception size doesn't match KBM DoF");
93 return Eigen::Map<const memoryx::KBM::Vector>(proprioception.data(), kbm.
getNDoF());
97 const std::vector<memoryx::KBM::Real>& position)
101 if (position.size() % nDim != 0)
110 const std::vector<memoryx::KBM::Real>& proprioception)
114 if (proprioception.size() % nDoF != 0)
123 const std::vector<memoryx::KBM::Real>&
data)
125 if (
data.size() % rows != 0)
130 VR_ASSERT(
data.size() % rows == 0);
131 int cols =
data.size() / rows;
132 return Eigen::Map<const memoryx::KBM::Matrix>(
data.data(), rows, cols);
137 auto it = kbms.find(name);
139 if (it == kbms.end())
141 ARMARX_WARNING <<
"a KBM with the name '" << name <<
"' does not exist";
161 const Ice::Current&
c)
166 if (kbms.find(name) != kbms.end())
168 ARMARX_ERROR <<
"a KBM with the name '" << name <<
"' already exists";
177 createdFromVirtualRobot[name] =
false;
178 ARMARX_INFO <<
"created a KBM with the name '" << name <<
"'";
182 const Ice::StringSeq& robotNodeNames,
183 const std::vector<memoryx::KBM::Real>& jointValueAverages,
184 const std::vector<memoryx::KBM::Real>& spreadAnglesSequence,
185 const std::string& tcpName,
187 const Ice::Current&
c)
192 if (robotNodeNames.size() != 7)
194 ARMARX_WARNING <<
"createArmar3KBM should only be used with all 7 joints";
197 if (jointValueAverages.size() != robotNodeNames.size())
199 ARMARX_INFO <<
"robotNodeNames: " << robotNodeNames.size();
200 ARMARX_INFO <<
"jointValueAverages: " << jointValueAverages.size();
201 ARMARX_ERROR <<
"jointValueAverages should have the same size as robotNodeNames";
204 if (spreadAnglesSequence.size() != robotNodeNames.size())
206 ARMARX_INFO <<
"robotNodeNames: " << robotNodeNames.size();
207 ARMARX_INFO <<
"spreadAngles: " << spreadAnglesSequence.size();
208 ARMARX_ERROR <<
"spreadAnglesSequence should have the same size as robotNodeNames";
214 if (kbms.find(name) != kbms.end())
216 ARMARX_ERROR <<
"a KBM with the name '" << name <<
"' already exists";
223 Eigen::Map<const memoryx::KBM::Vector> spreadAngles(spreadAnglesSequence.data(), spreadAnglesSequence.size());
229 std::time_t now = std::time(0);
230 std::tm* date = std::localtime(&now);
231 char when[256] = {0};
232 std::strftime(when,
sizeof(when),
"%Y-%m-%d-%H-%M-%S", date);
233 std::string baseFilename =
"data/evaluation/" + std::string(when) +
"-" + name;
235 std::ofstream metaFile(baseFilename +
"-create.txt", std::ios_base::app);
236 Eigen::Map<const memoryx::KBM::Vector> _jointValueAverages(jointValueAverages.data(), jointValueAverages.size());
238 if (metaFile.is_open())
240 metaFile <<
"kbm name: " << name << std::endl;
241 metaFile <<
"joint offsets: " << _jointValueAverages << std::endl;
242 metaFile <<
"spread angles: " << spreadAngles << std::endl;
250 VirtualRobot::RobotImporterFactoryPtr importer = VirtualRobot::RobotImporterFactory::fromFileExtension(
"xml", NULL);
251 std::string
filename(
"robots/ArmarIII/ArmarIII.xml");
252 VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(
filename);
257 ARMARX_ERROR <<
"the ArmarIII.xml file could not be loaded";
266 VirtualRobot::RobotNodeSetPtr nodeSet = VirtualRobot::RobotNodeSet::createRobotNodeSet(robot,
"ToolUseRightArm", robotNodeNames,
"Right Arm Base", tcpName,
true);
278 VirtualRobot::KinematicChainPtr chain;
280 chain.reset(
new VirtualRobot::KinematicChain(
"ToolUseRightArmChain", robot, nodeSet->getAllRobotNodes(), robot->getRobotNode(tcpName)));
293 ARMARX_IMPORTANT <<
"TCP GlobalPose before setting averages: " << chain->getTCP()->getGlobalPose();
295 Ice::FloatSeq jointValues;
297 for (
auto&
value : jointValueAverages)
299 jointValues.push_back(
value);
302 chain->setJointValues(jointValues);
303 ARMARX_VERBOSE <<
"node " << chain->getNode(0)->getName() <<
" is at: " << chain->getNode(0)->getJointValue();
304 ARMARX_IMPORTANT <<
"TCP GlobalPose after setting averages: " << chain->getTCP()->getGlobalPose();
306 VirtualRobot::RobotNodePtr FoR = chain->getKinematicRoot();
313 ARMARX_IMPORTANT <<
"FoR GlobalPose should be the identity matrix: " << FoR->getGlobalPose();
315 unsigned int nDoF = chain->getSize();
316 ARMARX_IMPORTANT <<
"degrees of freedom of the VirtualRobot's kinematic chain: " << nDoF;
323 createdFromVirtualRobot[name] =
true;
324 ARMARX_INFO <<
"created a KBM with the name '" << name <<
"'";
328 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
329 const std::vector<memoryx::KBM::Real>& positionSequence,
332 const Ice::Current&
c)
344 if (createdFromVirtualRobot[name])
346 ARMARX_ERROR <<
"the KBM " << name <<
" was created from a VirtualRobot, it does not support batch learning";
353 Eigen::Map<const memoryx::KBM::Matrix> proprioception =
mapProprioceptions(*kbm, proprioceptionSequence);
354 Eigen::Map<const memoryx::KBM::Matrix> position =
mapPositions(*kbm, positionSequence);
356 if (proprioception.cols() != position.cols())
358 ARMARX_ERROR <<
"proprioception and position contain different number of samples";
369 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
370 const std::vector<memoryx::KBM::Real>& positionSequence,
372 const Ice::Current&
c)
384 Eigen::Map<const memoryx::KBM::Matrix> proprioception =
mapProprioceptions(*kbm, proprioceptionSequence);
385 Eigen::Map<const memoryx::KBM::Matrix> position =
mapPositions(*kbm, positionSequence);
387 if (proprioception.cols() != position.cols())
389 ARMARX_ERROR <<
"proprioception and position contain different number of samples";
393 if (createdFromVirtualRobot[name])
398 ARMARX_IMPORTANT <<
"reversing proprioception order because KBM was created from VirtualRobot";
399 kbm->online(proprioception.colwise().reverse(), position, learningRate);
405 kbm->online(proprioception, position, learningRate);
410 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
411 const std::vector<memoryx::KBM::Real>& positionSequence,
413 const std::vector<memoryx::KBM::Real>& evaluationProprioceptionSequence,
414 const std::vector<memoryx::KBM::Real>& evaluationPositionSequence,
415 const Ice::Current&
c)
427 Eigen::Map<const memoryx::KBM::Matrix> _proprioception =
mapProprioceptions(*kbm, proprioceptionSequence);
428 Eigen::Map<const memoryx::KBM::Matrix> position =
mapPositions(*kbm, positionSequence);
430 Eigen::Map<const memoryx::KBM::Matrix> _evaluationProprioception =
mapProprioceptions(*kbm, evaluationProprioceptionSequence);
431 Eigen::Map<const memoryx::KBM::Matrix> evaluationPosition =
mapPositions(*kbm, evaluationPositionSequence);
433 if (_proprioception.cols() != position.cols())
435 ARMARX_ERROR <<
"proprioception and position contain different number of samples";
439 if (_evaluationProprioception.cols() != evaluationPosition.cols())
441 ARMARX_ERROR <<
"evaluation proprioception and evaluation position contain different number of samples";
448 if (createdFromVirtualRobot[name])
453 ARMARX_IMPORTANT <<
"reversing proprioception order because KBM was created from VirtualRobot";
454 proprioception = _proprioception.colwise().reverse();
455 evaluationProprioception = _evaluationProprioception.colwise().reverse();
459 proprioception = _proprioception;
460 evaluationProprioception = _evaluationProprioception;
464 ARMARX_IMPORTANT <<
"evaluation samples: " << evaluationProprioception.cols();
470 std::time_t now = std::time(0);
471 std::tm* date = std::localtime(&now);
472 char when[256] = {0};
473 std::strftime(when,
sizeof(when),
"%Y-%m-%d-%H-%M-%S", date);
474 std::string baseFilename =
"data/evaluation/" + std::string(when) +
"-" + name;
476 std::ofstream metaFile(baseFilename +
"-meta.txt", std::ios_base::app);
477 std::string evaluationFilename(baseFilename +
"-evaluation.txt");
478 std::ofstream evaluationFile(evaluationFilename, std::ios_base::app);
479 std::string trainingProprioceptionsFilename(baseFilename +
"-training-proprioceptions.txt");
480 std::ofstream trainingProprioceptionsFile(trainingProprioceptionsFilename, std::ios_base::app);
481 std::string trainingPositionsFilename(baseFilename +
"-training-positions.txt");
482 std::ofstream trainingPositionsFile(trainingPositionsFilename, std::ios_base::app);
483 std::string testProprioceptionsFilename(baseFilename +
"-test-proprioceptions.txt");
484 std::ofstream testProprioceptionsFile(testProprioceptionsFilename, std::ios_base::app);
485 std::string testPositionsFilename(baseFilename +
"-test-positions.txt");
486 std::ofstream testPositionsFile(testPositionsFilename, std::ios_base::app);
488 if (metaFile.is_open())
490 metaFile <<
"kbm name: " << name << std::endl;
491 metaFile <<
"learning rate: " << learningRate << std::endl;
492 metaFile <<
"degress of freedom: " << kbm->getNDoF() << std::endl;
493 metaFile <<
"dimensions: " << kbm->getNDim() << std::endl;
494 metaFile <<
"training samples: " << proprioception.cols() << std::endl;
495 metaFile <<
"test samples: " << evaluationProprioception.cols() << std::endl;
496 metaFile <<
"evaluation columns: mean, std, median, iqr, max" << std::endl;
501 if (!trainingProprioceptionsFile.is_open())
503 ARMARX_ERROR <<
"file " << trainingProprioceptionsFilename <<
" could not be opened / created";
506 if (!trainingPositionsFile.is_open())
508 ARMARX_ERROR <<
"file " << trainingPositionsFilename <<
" could not be opened / created";
511 if (!testProprioceptionsFile.is_open())
513 ARMARX_ERROR <<
"file " << testProprioceptionsFilename <<
" could not be opened / created";
516 if (!testPositionsFile.is_open())
518 ARMARX_ERROR <<
"file " << testPositionsFilename <<
" could not be opened / created";
521 trainingProprioceptionsFile << proprioception.transpose() << std::endl;
522 trainingPositionsFile << position.transpose() << std::endl;
523 testProprioceptionsFile << evaluationProprioception.transpose() << std::endl;
524 testPositionsFile << evaluationPosition.transpose() << std::endl;
526 trainingProprioceptionsFile.close();
527 trainingPositionsFile.close();
528 testProprioceptionsFile.close();
529 testPositionsFile.close();
534 if (!evaluationFile.is_open())
536 ARMARX_ERROR <<
"file " << evaluationFilename <<
" could not be opened / created";
541 evaluationFile << errors.
Mean <<
", " << errors.STD <<
", " << errors.Median <<
", " << errors.IQR <<
", " << errors.Max << std::endl;
543 for (
int i = 0; i < proprioception.cols(); i++)
545 kbm->online(proprioception.col(i), position.col(i), learningRate);
549 errors = kbm->getErrors(evaluationProprioception, evaluationPosition);
550 ARMARX_IMPORTANT <<
"online learning error after step " << (i + 1) <<
": " << errors;
551 evaluationFile << errors.Mean <<
", " << errors.STD <<
", " << errors.Median <<
", " << errors.IQR <<
", " << errors.Max << std::endl;
554 evaluationFile.close();
558 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
559 const Ice::Current&
c)
565 return std::vector<memoryx::KBM::Real>();
568 Eigen::Map<const memoryx::KBM::Matrix> proprioception =
mapProprioceptions(*kbm, proprioceptionSequence);
570 int nDim = kbm->getNDim();
571 int nSamples = proprioception.cols();
572 std::vector<memoryx::KBM::Real> predictionSequence(nDim * nSamples);
573 Eigen::Map<memoryx::KBM::Matrix> prediction(predictionSequence.data(), nDim, nSamples);
575 if (createdFromVirtualRobot[name])
580 prediction = kbm->predict(proprioception.colwise().reverse());
584 prediction = kbm->predict(proprioception);
587 ARMARX_INFO <<
"KBM '" << name <<
"' predicted: " << prediction.transpose();
588 return predictionSequence;
592 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
593 const std::vector<memoryx::KBM::Real>& positionSequence,
594 const Ice::Current&
c)
606 Eigen::Map<const memoryx::KBM::Matrix> proprioception =
mapProprioceptions(*kbm, proprioceptionSequence);
607 Eigen::Map<const memoryx::KBM::Matrix> position =
mapPositions(*kbm, positionSequence);
609 if (proprioception.cols() != position.cols())
611 ARMARX_ERROR <<
"proprioception and position contain different number of samples";
619 if (createdFromVirtualRobot[name])
624 errors = kbm->getErrors(proprioception.colwise().reverse(), position);
628 errors = kbm->getErrors(proprioception, position);
636 Eigen::Map<const memoryx::KBM::Matrix> proprioception =
mapMatrix(nDoF, proprioceptionAccumulator);
637 Eigen::Map<const memoryx::KBM::Matrix> position =
mapMatrix(nDim, positionAccumulator);
639 ARMARX_VERBOSE <<
"proprioception samples: " << proprioception.cols();
642 ARMARX_VERBOSE <<
"proprioception minima: " << proprioception.rowwise().minCoeff().transpose();
643 ARMARX_VERBOSE <<
"proprioception maxima: " << proprioception.rowwise().maxCoeff().transpose();
644 ARMARX_VERBOSE <<
"proprioception average: " << proprioception.rowwise().mean().transpose();
645 ARMARX_VERBOSE <<
"position minima: " << position.rowwise().minCoeff().transpose();
646 ARMARX_VERBOSE <<
"position maxima: " << position.rowwise().maxCoeff().transpose();
647 ARMARX_VERBOSE <<
"position average: " << position.rowwise().mean().transpose();
652 Eigen::Map<const memoryx::KBM::Matrix> rawJointValues =
mapMatrix(nDoF, rawJointValuesAccumulator);
654 ARMARX_VERBOSE <<
"raw jointValue samples: " << rawJointValues.cols();
656 std::vector<memoryx::KBM::Real> result(nDoF);
657 Eigen::Map<memoryx::KBM::Vector> averages(result.data(), nDoF);
658 averages = rawJointValues.rowwise().mean();
660 Ice::DoubleSeq resultFloat(result.begin(), result.end());
666 Eigen::Map<const memoryx::KBM::Matrix> proprioceptions =
mapMatrix(nDoF, proprioceptionAccumulator);
668 ARMARX_VERBOSE <<
"proprioception samples: " << proprioceptions.cols();
670 std::vector<memoryx::KBM::Real> result(nDoF);
671 Eigen::Map<memoryx::KBM::Vector> spreadAngles(result.data(), nDoF);
678 for (
int i = 0; i < nDoF; i++)
680 spreadAngles[i] = fmin(fabs(leftSpreadAngles[i]), fabs(rightSpreadAngles[i]));
685 Ice::DoubleSeq resultFloat(result.begin(), result.end());
690 const Ice::Current&
c)
692 if (proprioceptionAccumulator.size() != 0)
694 ARMARX_ERROR <<
"proprioception accumulator should be empty, when using setting it from raw joint accumulator";
697 if (rawJointValuesAccumulator.size() % rawJointValuesAverages.size() != 0)
699 ARMARX_ERROR <<
"rawJointValuesAverages size is incompatible to accumulator size";
702 ARMARX_INFO <<
"rawJointValuesAccumualtor: " << rawJointValuesAccumulator;
703 std::vector<memoryx::KBM::Real> proprioceptionsFromRawJointAccumulator;
706 for (
auto jointValue : rawJointValuesAccumulator)
708 if (i == rawJointValuesAverages.size())
713 float offset = rawJointValuesAverages[i];
719 proprioceptionsFromRawJointAccumulator.push_back(jointValue - offset);
722 ARMARX_INFO <<
"proprioceptionsFromRawJointAccumulator: " << proprioceptionsFromRawJointAccumulator;
723 proprioceptionAccumulator = proprioceptionsFromRawJointAccumulator;
732 Eigen::Map<const memoryx::KBM::Matrix> positions =
mapMatrix(nDim, positionAccumulator);
733 minima = positions.rowwise().minCoeff();
734 maxima = positions.rowwise().maxCoeff();
741 const Ice::Current&
c)
743 online(name, proprioceptionAccumulator, positionAccumulator, learningRate,
c);
748 const Ice::Current&
c)
750 onlineVerbose(name, proprioceptionAccumulator, positionAccumulator, learningRate, evaluationProprioceptionAccumulator, evaluationPositionAccumulator,
c);
756 const Ice::Current&
c)
758 batch(name, proprioceptionAccumulator, positionAccumulator, method, threshold,
c);
763 printErrors(name, proprioceptionAccumulator, positionAccumulator,
c);
768 predict(name, proprioceptionAccumulator,
c);
784 positionAccumulator.insert(positionAccumulator.end(), position.begin(), position.end());
794 proprioceptionAccumulator.insert(proprioceptionAccumulator.end(), proprioception.begin(), proprioception.end());
804 rawJointValuesAccumulator.insert(rawJointValuesAccumulator.end(), rawJointValuesSequence.begin(), rawJointValuesSequence.end());
814 evaluationPositionAccumulator.insert(evaluationPositionAccumulator.end(), position.begin(), position.end());
824 evaluationProprioceptionAccumulator.insert(evaluationProprioceptionAccumulator.end(), proprioception.begin(), proprioception.end());
830 const std::vector<memoryx::KBM::Real>& targetPosition,
831 const Ice::Current&
c)
841 return std::vector<memoryx::KBM::Real>();
844 Eigen::Map<const memoryx::KBM::Vector>
target(
mapPosition(*kbm, targetPosition));
849 std::vector<memoryx::KBM::Real> result(kbm->getNDoF());
850 Eigen::Map<memoryx::KBM::Vector> solution(result.data(), kbm->getNDoF());
858 for (
unsigned int i = 0; i < solutions.size(); ++i)
865 if (createdFromVirtualRobot[name])
867 ARMARX_ERROR <<
"solveGlobalIK does not yet support KBMs created from Virtual Robot!";
874 const std::vector<memoryx::KBM::Real>& targetPosition,
875 const std::vector<memoryx::KBM::Real>& currentPosition,
876 const std::vector<memoryx::KBM::Real>& currentProprioception,
877 const std::vector<memoryx::KBM::Real>& lowerProprioceptionLimitsSequence,
878 const std::vector<memoryx::KBM::Real>& upperProprioceptionLimitsSequence,
879 const Ice::Current&
c)
889 return std::vector<memoryx::KBM::Real>();
892 Eigen::Map<const memoryx::KBM::Vector>
target(
mapPosition(*kbm, targetPosition));
893 Eigen::Map<const memoryx::KBM::Vector> current(
mapPosition(*kbm, currentPosition));
894 Eigen::Map<const memoryx::KBM::Vector> proprioception(
mapProprioception(*kbm, currentProprioception));
895 Eigen::Map<const memoryx::KBM::Vector> lowerProprioceptionLimits(
mapProprioception(*kbm, lowerProprioceptionLimitsSequence));
896 Eigen::Map<const memoryx::KBM::Vector> upperProprioceptionLimits(
mapProprioception(*kbm, upperProprioceptionLimitsSequence));
901 if (minima.size() !=
target.size())
903 ARMARX_ERROR <<
"minima and target have different size";
904 return std::vector<memoryx::KBM::Real>();
907 if (maxima.size() !=
target.size())
910 ARMARX_ERROR <<
"maxima and target have different size";
911 return std::vector<memoryx::KBM::Real>();
914 for (
int i = 0; i < kbm->getNDim(); i++)
916 if (
target[i] < minima[i] - 90)
918 ARMARX_ERROR <<
"target[" << i <<
"] = " <<
target[i] <<
" is smaller than minima " << minima[i];
919 return std::vector<memoryx::KBM::Real>();
922 if (
target[i] > maxima[i] + 90)
924 ARMARX_ERROR <<
"target[" << i <<
"] = " <<
target[i] <<
" is greater than maxima " << maxima[i];
925 return std::vector<memoryx::KBM::Real>();
932 std::vector<memoryx::KBM::Real> result(kbm->getNDoF());
933 Eigen::Map<memoryx::KBM::Vector> solution(result.data(), kbm->getNDoF());
940 if (createdFromVirtualRobot[name])
945 ARMARX_IMPORTANT <<
"reversing proprioception and limits order because KBM was created from VirtualRobot";
946 solved =
KBMDifferentialIK::solveMany(*kbm,
target, current, proprioception.reverse(), lowerProprioceptionLimits.reverse(), upperProprioceptionLimits.reverse(), solution);
953 if (createdFromVirtualRobot[name])
959 solution = solution.colwise().reverse();
984 return LO +
static_cast <float>(rand()) / (
static_cast <float>(RAND_MAX / (HI - LO)));
992 float stepSizeFactor,
1001 if (positionDeltas.norm() > maxStepSize)
1003 positionDeltas *= maxStepSize / positionDeltas.norm();
1015 #ifdef KBM_USE_DOUBLE_PRECISION
1032 if (lowerProprioceptionLimits.size() != upperProprioceptionLimits.size())
1037 int n = lowerProprioceptionLimits.size();
1040 for (
int i = 0; i < n; i++)
1042 float l = lowerProprioceptionLimits(i);
1043 float u = upperProprioceptionLimits(i);
1058 int n = solution.size();
1060 if (lowerProprioceptionLimits.size() != n)
1062 ARMARX_ERROR_S <<
"lower proprioception limits have wrong length: " << lowerProprioceptionLimits.size() <<
", should be " << n;
1065 if (upperProprioceptionLimits.size() != n)
1067 ARMARX_ERROR_S <<
"upper proprioception limits have wrong length: " << upperProprioceptionLimits.size() <<
", should be " << n;
1073 for (
int i = 0; i < n; i++)
1075 if ((solution(i) < lowerProprioceptionLimits(i)) || (solution(i) > upperProprioceptionLimits(i)))
1085 Eigen::Map<memoryx::KBM::Vector>& solution,
1092 int n = solution.size();
1094 if (lowerProprioceptionLimits.size() != n)
1096 ARMARX_ERROR_S <<
"lower proprioception limits have wrong length: " << lowerProprioceptionLimits.size() <<
", should be " << n;
1099 if (upperProprioceptionLimits.size() != n)
1101 ARMARX_ERROR_S <<
"upper proprioception limits have wrong length: " << upperProprioceptionLimits.size() <<
", should be " << n;
1107 bool inLimits =
true;
1109 for (
int i = 0; i < n; i++)
1111 if (solution(i) < lowerProprioceptionLimits(i))
1113 solution(i) = lowerProprioceptionLimits(i);
1117 if (solution(i) > upperProprioceptionLimits(i))
1119 solution(i) = upperProprioceptionLimits(i);
1133 Eigen::Map<memoryx::KBM::Vector>& solution,
1136 float positionTolerance,
1138 bool requireImprovment,
1140 float stepSizeFactor,
1144 float bestDistance = FLT_MAX;
1145 bool inLimits =
false;
1147 std::vector<memoryx::KBM::Real> newSolutionSequence(kbm.
getNDoF());
1148 Eigen::Map<memoryx::KBM::Vector> newSolution(newSolutionSequence.data(), kbm.
getNDoF());
1150 for (
int i = 0; i < maxSolves; i++)
1156 startProprioception = currentProprioception;
1160 startProprioception =
randomProprioception(lowerProprioceptionLimits, upperProprioceptionLimits);
1163 ARMARX_IMPORTANT_S <<
"iteration " << (i + 1) <<
" proprioception: " << startProprioception.transpose();
1170 KBMDifferentialIK::solve(kbm, targetPosition, startPosition, startProprioception, newSolution, positionTolerance, minimumDelta, requireImprovment, maxSteps, stepSizeFactor, maxStepSize);
1185 float distance = (targetPosition - testPosition).
norm();
1197 ARMARX_IMPORTANT_S <<
"solution was not within limits, but enforced limits so now it is";
1203 testPosition = kbm.
predict(newSolution);
1215 if (applyLimits && !currentInLimits)
1219 ARMARX_ERROR_S <<
"lower proprioception limits: " << lowerProprioceptionLimits;
1220 ARMARX_ERROR_S <<
"upper proprioception limits: " << upperProprioceptionLimits;
1223 if (inLimits && !currentInLimits)
1225 ARMARX_IMPORTANT_S <<
"ignoring solution because we already found one that is within the limits";
1230 float distance = (targetPosition - newPosition).
norm();
1234 if ((
distance < bestDistance) || (currentInLimits && !inLimits))
1237 inLimits = currentInLimits;
1238 solution = newSolution;
1241 if (inLimits && (bestDistance < positionTolerance))
1243 ARMARX_IMPORTANT_S <<
"found a solution within the limits with small distance, aborting search";
1249 ARMARX_IMPORTANT_S <<
"final distance: " << bestDistance <<
", in limits: " << inLimits;
1251 if (bestDistance < positionTolerance)
1265 Eigen::Map<memoryx::KBM::Vector>& solution,
1266 float positionTolerance,
1268 bool requireImprovment,
1270 float stepSizeFactor,
1274 assert(targetPosition.size() == kbm.
getNDim());
1275 assert(currentPosition.size() == kbm.
getNDim());
1276 assert(currentProprioception.size() == kbm.
getNDoF());
1277 assert(solution.size() == kbm.
getNDoF());
1282 solution = currentProprioception;
1287 float bestDistance = (targetPosition - currentPosition).
norm();
1292 if (bestDistance <= positionTolerance)
1312 for (
int step = 0; step < maxSteps; ++step)
1322 simulatedProprioception +=
deltas;
1327 predictedPosition = kbm.
predict(simulatedProprioception);
1333 float distance = (targetPosition - predictedPosition).
norm();
1338 solution = simulatedProprioception;
1345 if (requireImprovment && (
distance >= bestDistance))
1356 solution = simulatedProprioception;
1363 if (
deltas.norm() < minimumDelta)
1374 std::vector<std::string> kbmKeys;
1376 for (
auto it : kbms)
1378 kbmKeys.push_back(it.first);
1386 positionAccumulator.clear();
1387 proprioceptionAccumulator.clear();
1388 rawJointValuesAccumulator.clear();
1391 void KBMComponent::storeToMemory(
const std::string& kbmName,
const std::string& nodeSetName,
const std::string& referenceFrameName,
const std::string& robotName,
const Ice::Current&
c)
1397 auto kbmSeg = this->longtermMemoryPrx->getKBMSegment();
1402 kbmSeg->addEntity(kbmData);
1407 ARMARX_WARNING <<
"Could not store KBM! No KBM segment in longterm memory!";
1414 void KBMComponent::restoreFromMemory(
const std::string& kbmName,
const std::string& nodeSetName,
const std::string& referenceFrameName,
const std::string& robotName,
const Ice::Current&
c)
1417 auto kbmSeg = this->longtermMemoryPrx->getKBMSegment();
1418 std::string kbmEntityName = robotName +
"_" + referenceFrameName +
"_" + nodeSetName;
1420 if (kbmSeg && kbmSeg->hasEntityByName(kbmEntityName))
1422 auto entity = kbmSeg->getEntityByName(kbmEntityName);
1428 int nDoF = robot->getRobotNodeSet(nodeSetName)->getSize();
1433 createdFromVirtualRobot[kbmName] =
false;
1437 ARMARX_WARNING <<
"Could not restore KBM entity specified by: " << kbmEntityName;
1446 bool KBMComponent::isInMemory(
const std::string& nodeSetName,
const std::string& referenceFrameName,
const std::string& robotName,
const Ice::Current&
c)
1448 std::string kbmEntityName = robotName +
"_" + referenceFrameName +
"_" + nodeSetName;
1450 return (this->longtermMemoryPrx->getKBMSegment() && this->longtermMemoryPrx->getKBMSegment()->hasEntityByName(kbmEntityName));