KBMComponent.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package MemoryX::ArmarXObjects::KBMComponent
19  * @author Jonas Rauber ( kit at jonasrauber dot de )
20  * @date 2014
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #include "KBMComponent.h"
26 #include <VirtualRobot/MathTools.h>
29 
30 #include <RobotAPI/interface/core/RobotState.h>
32 
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>
38 
39 #include <fstream>
40 #include <cmath>
41 
42 
43 namespace armarx
44 {
46  {
47  usingProxy(getProperty<std::string>("LongtermMemoryName").getValue());
48  usingProxy(getProperty<std::string>("RobotStateComponentName").getValue());
49  }
50 
51 
53  {
54  this->longtermMemoryPrx = getProxy<memoryx::LongtermMemoryInterfacePrx>(getProperty<std::string>("LongtermMemoryName").getValue());
55  this->robotStateComponentPrx = getProxy<armarx::RobotStateComponentInterfacePrx>(getProperty<std::string>("RobotStateComponentName").getValue());
56  }
57 
58 
60  {
61  }
62 
63 
65  {
66  }
67 
69  {
71  }
72 
73 
74  /*
75  *
76  *
77  * Helper methods
78  *
79  *
80  */
81 
82  Eigen::Map<const memoryx::KBM::Vector> KBMComponent::mapPosition(const memoryx::KBM::Models::KBM& kbm,
83  const std::vector<memoryx::KBM::Real>& position)
84  {
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());
87  }
88 
89  Eigen::Map<const memoryx::KBM::Vector> KBMComponent::mapProprioception(const memoryx::KBM::Models::KBM& kbm,
90  const std::vector<memoryx::KBM::Real>& proprioception)
91  {
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());
94  }
95 
96  Eigen::Map<const memoryx::KBM::Matrix> KBMComponent::mapPositions(const memoryx::KBM::Models::KBM& kbm,
97  const std::vector<memoryx::KBM::Real>& position)
98  {
99  int nDim = kbm.getNDim();
100 
101  if (position.size() % nDim != 0)
102  {
103  ARMARX_ERROR << "position has an invalid length";
104  }
105 
106  return mapMatrix(nDim, position);
107  }
108 
109  Eigen::Map<const memoryx::KBM::Matrix> KBMComponent::mapProprioceptions(const memoryx::KBM::Models::KBM& kbm,
110  const std::vector<memoryx::KBM::Real>& proprioception)
111  {
112  int nDoF = kbm.getNDoF();
113 
114  if (proprioception.size() % nDoF != 0)
115  {
116  ARMARX_ERROR << "proprioception has an invalid length";
117  }
118 
119  return mapMatrix(nDoF, proprioception);
120  }
121 
122  Eigen::Map<const memoryx::KBM::Matrix> KBMComponent::mapMatrix(int rows,
123  const std::vector<memoryx::KBM::Real>& data)
124  {
125  if (data.size() % rows != 0)
126  {
127  ARMARX_ERROR << "data has an invalid length";
128  }
129 
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);
133  }
134 
136  {
137  auto it = kbms.find(name);
138 
139  if (it == kbms.end())
140  {
141  ARMARX_WARNING << "a KBM with the name '" << name << "' does not exist";
142  return memoryx::KBM::Models::KBM_ptr(); // null pointer
143  }
144 
145  return it->second;
146  }
147 
148 
149  /*
150  *
151  *
152  * KBM Component interface methods
153  *
154  *
155  */
156 
157  void KBMComponent::createKBM(const std::string& name,
158  Ice::Int nDoF,
159  Ice::Int dim,
160  Ice::Float spreadAngle,
161  const Ice::Current& c)
162  {
163  /*
164  * Check if a KBM with the given name already exists
165  */
166  if (kbms.find(name) != kbms.end())
167  {
168  ARMARX_ERROR << "a KBM with the name '" << name << "' already exists";
169  return;
170  }
171 
172  /*
173  * Create the KBM
174  */
175  memoryx::KBM::Models::KBM_ptr kbm(new memoryx::KBM::Models::KBM(nDoF, dim, spreadAngle));
176  kbms[name] = kbm;
177  createdFromVirtualRobot[name] = false;
178  ARMARX_INFO << "created a KBM with the name '" << name << "'";
179  }
180 
181  void KBMComponent::createArmar3KBM(const std::string& 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,
186  bool useOrientation,
187  const Ice::Current& c)
188  {
189  /*
190  * check parameters
191  */
192  if (robotNodeNames.size() != 7)
193  {
194  ARMARX_WARNING << "createArmar3KBM should only be used with all 7 joints";
195  }
196 
197  if (jointValueAverages.size() != robotNodeNames.size())
198  {
199  ARMARX_INFO << "robotNodeNames: " << robotNodeNames.size();
200  ARMARX_INFO << "jointValueAverages: " << jointValueAverages.size();
201  ARMARX_ERROR << "jointValueAverages should have the same size as robotNodeNames";
202  }
203 
204  if (spreadAnglesSequence.size() != robotNodeNames.size())
205  {
206  ARMARX_INFO << "robotNodeNames: " << robotNodeNames.size();
207  ARMARX_INFO << "spreadAngles: " << spreadAnglesSequence.size();
208  ARMARX_ERROR << "spreadAnglesSequence should have the same size as robotNodeNames";
209  }
210 
211  /*
212  * Check if a KBM with the given name already exists
213  */
214  if (kbms.find(name) != kbms.end())
215  {
216  ARMARX_ERROR << "a KBM with the name '" << name << "' already exists";
217  return;
218  }
219 
220  /*
221  * spread angles
222  */
223  Eigen::Map<const memoryx::KBM::Vector> spreadAngles(spreadAnglesSequence.data(), spreadAnglesSequence.size());
224  ARMARX_IMPORTANT << "spreadAngles: " << spreadAngles.transpose();
225 
226  /*
227  * Save meta data
228  */
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;
234 
235  std::ofstream metaFile(baseFilename + "-create.txt", std::ios_base::app);
236  Eigen::Map<const memoryx::KBM::Vector> _jointValueAverages(jointValueAverages.data(), jointValueAverages.size());
237 
238  if (metaFile.is_open())
239  {
240  metaFile << "kbm name: " << name << std::endl;
241  metaFile << "joint offsets: " << _jointValueAverages << std::endl;
242  metaFile << "spread angles: " << spreadAngles << std::endl;
243  }
244 
245  metaFile.close();
246 
247  /*
248  * Load VirtualRobot
249  */
250  VirtualRobot::RobotImporterFactoryPtr importer = VirtualRobot::RobotImporterFactory::fromFileExtension("xml", NULL);
251  std::string filename("robots/ArmarIII/ArmarIII.xml");
252  VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filename);
253  VirtualRobot::RobotPtr robot = importer->loadFromFile(filename, VirtualRobot::RobotIO::eStructure);
254 
255  if (!robot)
256  {
257  ARMARX_ERROR << "the ArmarIII.xml file could not be loaded";
258  }
259 
260  VR_ASSERT(robot);
261 
262  /*
263  * Create a robot node set with the names of the active joints
264  */
265  //VirtualRobot::RobotNodeSetPtr nodeSet = robot->getRobotNodeSet("TorsoRightArm");
266  VirtualRobot::RobotNodeSetPtr nodeSet = VirtualRobot::RobotNodeSet::createRobotNodeSet(robot, "ToolUseRightArm", robotNodeNames, "Right Arm Base", tcpName, true);
267 
268  if (!nodeSet)
269  {
270  ARMARX_ERROR << "the nodeSet could not be created";
271  }
272 
273  VR_ASSERT(nodeSet);
274 
275  /*
276  * Create a kinematic chain from the robot node set
277  */
278  VirtualRobot::KinematicChainPtr chain;
279  //chain.reset(new VirtualRobot::KinematicChain("TorsoRightArmChain",robot,nodeSet->getAllRobotNodes(),robot->getRobotNode("Wrist 2 R")));
280  chain.reset(new VirtualRobot::KinematicChain("ToolUseRightArmChain", robot, nodeSet->getAllRobotNodes(), robot->getRobotNode(tcpName)));
281 
282  if (!chain)
283  {
284  ARMARX_ERROR << "chain could not be created";
285  }
286 
287  VR_ASSERT(chain);
288 
289  /*
290  * Set joint values to their average position,
291  * so that samples are distributed around zero
292  */
293  ARMARX_IMPORTANT << "TCP GlobalPose before setting averages: " << chain->getTCP()->getGlobalPose();
294  ARMARX_IMPORTANT << "setting averages: " << jointValueAverages;
295  Ice::FloatSeq jointValues;
296 
297  for (auto& value : jointValueAverages)
298  {
299  jointValues.push_back(value);
300  }
301 
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();
305 
306  VirtualRobot::RobotNodePtr FoR = chain->getKinematicRoot();
307 
308  VR_ASSERT(FoR);
309 
310  /*
311  * TODO: print warning if not
312  */
313  ARMARX_IMPORTANT << "FoR GlobalPose should be the identity matrix: " << FoR->getGlobalPose();
314 
315  unsigned int nDoF = chain->getSize();
316  ARMARX_IMPORTANT << "degrees of freedom of the VirtualRobot's kinematic chain: " << nDoF;
317 
318  /*
319  * Create the KBM
320  */
321  memoryx::KBM::Models::KBM_ptr kbm(memoryx::KBM::Models::KBM::createFromVirtualRobot(chain, FoR, spreadAngles, useOrientation));
322  kbms[name] = kbm;
323  createdFromVirtualRobot[name] = true;
324  ARMARX_INFO << "created a KBM with the name '" << name << "'";
325  }
326 
327  void KBMComponent::batch(const std::string& name,
328  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
329  const std::vector<memoryx::KBM::Real>& positionSequence,
330  Ice::Int method,
331  Ice::Float threshold,
332  const Ice::Current& c)
333  {
335 
336  if (!kbm)
337  {
338  return;
339  }
340 
341  /*
342  * It doesn't make sense to do batch learning on KBMs created from a VirtualRobot.
343  */
344  if (createdFromVirtualRobot[name])
345  {
346  ARMARX_ERROR << "the KBM " << name << " was created from a VirtualRobot, it does not support batch learning";
347  return;
348  }
349 
350  /*
351  * This maps the data column wise.
352  */
353  Eigen::Map<const memoryx::KBM::Matrix> proprioception = mapProprioceptions(*kbm, proprioceptionSequence);
354  Eigen::Map<const memoryx::KBM::Matrix> position = mapPositions(*kbm, positionSequence);
355 
356  if (proprioception.cols() != position.cols())
357  {
358  ARMARX_ERROR << "proprioception and position contain different number of samples";
359  return;
360  }
361 
362  /*
363  * Start batch learning
364  */
365  kbm->batch(proprioception, position, (memoryx::KBM::Models::KBM::Optimization)method, threshold);
366  }
367 
368  void KBMComponent::online(const std::string& name,
369  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
370  const std::vector<memoryx::KBM::Real>& positionSequence,
371  Ice::Float learningRate,
372  const Ice::Current& c)
373  {
375 
376  if (!kbm)
377  {
378  return;
379  }
380 
381  /*
382  * This maps the data column wise.
383  */
384  Eigen::Map<const memoryx::KBM::Matrix> proprioception = mapProprioceptions(*kbm, proprioceptionSequence);
385  Eigen::Map<const memoryx::KBM::Matrix> position = mapPositions(*kbm, positionSequence);
386 
387  if (proprioception.cols() != position.cols())
388  {
389  ARMARX_ERROR << "proprioception and position contain different number of samples";
390  return;
391  }
392 
393  if (createdFromVirtualRobot[name])
394  {
395  /*
396  * support VirtualRobot KBMs by reversing joint order
397  */
398  ARMARX_IMPORTANT << "reversing proprioception order because KBM was created from VirtualRobot";
399  kbm->online(proprioception.colwise().reverse(), position, learningRate);
400  }
401  else
402  {
403  // TODO: why does this work: KBM expects a Matrix and should not be
404  // compatible with a Map of Matrix without additional modifications
405  kbm->online(proprioception, position, learningRate);
406  }
407  }
408 
409  void KBMComponent::onlineVerbose(const std::string& name,
410  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
411  const std::vector<memoryx::KBM::Real>& positionSequence,
412  Ice::Float learningRate,
413  const std::vector<memoryx::KBM::Real>& evaluationProprioceptionSequence,
414  const std::vector<memoryx::KBM::Real>& evaluationPositionSequence,
415  const Ice::Current& c)
416  {
418 
419  if (!kbm)
420  {
421  return;
422  }
423 
424  /*
425  * This maps the data column wise.
426  */
427  Eigen::Map<const memoryx::KBM::Matrix> _proprioception = mapProprioceptions(*kbm, proprioceptionSequence);
428  Eigen::Map<const memoryx::KBM::Matrix> position = mapPositions(*kbm, positionSequence);
429 
430  Eigen::Map<const memoryx::KBM::Matrix> _evaluationProprioception = mapProprioceptions(*kbm, evaluationProprioceptionSequence);
431  Eigen::Map<const memoryx::KBM::Matrix> evaluationPosition = mapPositions(*kbm, evaluationPositionSequence);
432 
433  if (_proprioception.cols() != position.cols())
434  {
435  ARMARX_ERROR << "proprioception and position contain different number of samples";
436  return;
437  }
438 
439  if (_evaluationProprioception.cols() != evaluationPosition.cols())
440  {
441  ARMARX_ERROR << "evaluation proprioception and evaluation position contain different number of samples";
442  return;
443  }
444 
445  memoryx::KBM::Matrix proprioception;
446  memoryx::KBM::Matrix evaluationProprioception;
447 
448  if (createdFromVirtualRobot[name])
449  {
450  /*
451  * support VirtualRobot KBMs by reversing joint order
452  */
453  ARMARX_IMPORTANT << "reversing proprioception order because KBM was created from VirtualRobot";
454  proprioception = _proprioception.colwise().reverse();
455  evaluationProprioception = _evaluationProprioception.colwise().reverse();
456  }
457  else
458  {
459  proprioception = _proprioception;
460  evaluationProprioception = _evaluationProprioception;
461  }
462 
463  ARMARX_IMPORTANT << "training samples: " << proprioception.cols();
464  ARMARX_IMPORTANT << "evaluation samples: " << evaluationProprioception.cols();
465 
466  /*
467  * Prepare file
468  */
469 
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;
475 
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);
487 
488  if (metaFile.is_open())
489  {
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;
497  }
498 
499  metaFile.close();
500 
501  if (!trainingProprioceptionsFile.is_open())
502  {
503  ARMARX_ERROR << "file " << trainingProprioceptionsFilename << " could not be opened / created";
504  }
505 
506  if (!trainingPositionsFile.is_open())
507  {
508  ARMARX_ERROR << "file " << trainingPositionsFilename << " could not be opened / created";
509  }
510 
511  if (!testProprioceptionsFile.is_open())
512  {
513  ARMARX_ERROR << "file " << testProprioceptionsFilename << " could not be opened / created";
514  }
515 
516  if (!testPositionsFile.is_open())
517  {
518  ARMARX_ERROR << "file " << testPositionsFilename << " could not be opened / created";
519  }
520 
521  trainingProprioceptionsFile << proprioception.transpose() << std::endl;
522  trainingPositionsFile << position.transpose() << std::endl;
523  testProprioceptionsFile << evaluationProprioception.transpose() << std::endl;
524  testPositionsFile << evaluationPosition.transpose() << std::endl;
525 
526  trainingProprioceptionsFile.close();
527  trainingPositionsFile.close();
528  testProprioceptionsFile.close();
529  testPositionsFile.close();
530 
531  /*
532  * Learn, evaluate and write to file
533  */
534  if (!evaluationFile.is_open())
535  {
536  ARMARX_ERROR << "file " << evaluationFilename << " could not be opened / created";
537  }
538 
539  memoryx::KBM::Models::KBM::ErrorValuesType errors = kbm->getErrors(evaluationProprioception, evaluationPosition);
540  ARMARX_IMPORTANT << "online learning before learning: " << errors;
541  evaluationFile << errors.Mean << ", " << errors.STD << ", " << errors.Median << ", " << errors.IQR << ", " << errors.Max << std::endl;
542 
543  for (int i = 0; i < proprioception.cols(); i++)
544  {
545  kbm->online(proprioception.col(i), position.col(i), learningRate);
546  /*
547  * TODO: maybe use my own error calculation, including standard deviation, etc.
548  */
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;
552  }
553 
554  evaluationFile.close();
555  }
556 
557  std::vector<memoryx::KBM::Real> KBMComponent::predict(const std::string& name,
558  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
559  const Ice::Current& c)
560  {
562 
563  if (!kbm)
564  {
565  return std::vector<memoryx::KBM::Real>();
566  }
567 
568  Eigen::Map<const memoryx::KBM::Matrix> proprioception = mapProprioceptions(*kbm, proprioceptionSequence);
569 
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);
574 
575  if (createdFromVirtualRobot[name])
576  {
577  /*
578  * support VirtualRobot KBMs by reversing joint order
579  */
580  prediction = kbm->predict(proprioception.colwise().reverse());
581  }
582  else
583  {
584  prediction = kbm->predict(proprioception);
585  }
586 
587  ARMARX_INFO << "KBM '" << name << "' predicted: " << prediction.transpose();
588  return predictionSequence;
589  }
590 
591  void KBMComponent::printErrors(const std::string& name,
592  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
593  const std::vector<memoryx::KBM::Real>& positionSequence,
594  const Ice::Current& c)
595  {
597 
598  if (!kbm)
599  {
600  return;
601  }
602 
603  /*
604  * This maps the data column wise.
605  */
606  Eigen::Map<const memoryx::KBM::Matrix> proprioception = mapProprioceptions(*kbm, proprioceptionSequence);
607  Eigen::Map<const memoryx::KBM::Matrix> position = mapPositions(*kbm, positionSequence);
608 
609  if (proprioception.cols() != position.cols())
610  {
611  ARMARX_ERROR << "proprioception and position contain different number of samples";
612  return;
613  }
614 
615  ARMARX_IMPORTANT << "samples: " << proprioception.cols();
616 
618 
619  if (createdFromVirtualRobot[name])
620  {
621  /*
622  * support VirtualRobot KBMs by reversing joint order
623  */
624  errors = kbm->getErrors(proprioception.colwise().reverse(), position);
625  }
626  else
627  {
628  errors = kbm->getErrors(proprioception, position);
629  }
630 
631  ARMARX_IMPORTANT << "KBM '" << name << "' error: " << errors;
632  }
633 
634  void KBMComponent::printAccumulatorStatistics(int nDim, int nDoF, const Ice::Current& c)
635  {
636  Eigen::Map<const memoryx::KBM::Matrix> proprioception = mapMatrix(nDoF, proprioceptionAccumulator);
637  Eigen::Map<const memoryx::KBM::Matrix> position = mapMatrix(nDim, positionAccumulator);
638 
639  ARMARX_VERBOSE << "proprioception samples: " << proprioception.cols();
640  ARMARX_VERBOSE << "position samples: " << position.cols();
641 
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();
648  }
649 
650  Ice::DoubleSeq KBMComponent::getRawJointValuesAverages(int nDoF, const Ice::Current& c)
651  {
652  Eigen::Map<const memoryx::KBM::Matrix> rawJointValues = mapMatrix(nDoF, rawJointValuesAccumulator);
653 
654  ARMARX_VERBOSE << "raw jointValue samples: " << rawJointValues.cols();
655 
656  std::vector<memoryx::KBM::Real> result(nDoF);
657  Eigen::Map<memoryx::KBM::Vector> averages(result.data(), nDoF);
658  averages = rawJointValues.rowwise().mean();
659 
660  Ice::DoubleSeq resultFloat(result.begin(), result.end());
661  return resultFloat;
662  }
663 
664  Ice::DoubleSeq KBMComponent::getSpreadAngles(int nDoF, const Ice::Current& c)
665  {
666  Eigen::Map<const memoryx::KBM::Matrix> proprioceptions = mapMatrix(nDoF, proprioceptionAccumulator);
667 
668  ARMARX_VERBOSE << "proprioception samples: " << proprioceptions.cols();
669 
670  std::vector<memoryx::KBM::Real> result(nDoF);
671  Eigen::Map<memoryx::KBM::Vector> spreadAngles(result.data(), nDoF);
672 
673  memoryx::KBM::Vector leftSpreadAngles = proprioceptions.rowwise().minCoeff();
674  memoryx::KBM::Vector rightSpreadAngles = proprioceptions.rowwise().maxCoeff();
675  ARMARX_VERBOSE << "leftSpreadAngles: " << leftSpreadAngles;
676  ARMARX_VERBOSE << "rightSpreadAngles: " << rightSpreadAngles;
677 
678  for (int i = 0; i < nDoF; i++)
679  {
680  spreadAngles[i] = fmin(fabs(leftSpreadAngles[i]), fabs(rightSpreadAngles[i]));
681  }
682 
683  ARMARX_VERBOSE << "data spreadAngles: " << spreadAngles;
684 
685  Ice::DoubleSeq resultFloat(result.begin(), result.end());
686  return resultFloat;
687  }
688 
689  void KBMComponent::setProprioceptionAccumulatorFromRawJointAccumulator(const std::vector<memoryx::KBM::Real>& rawJointValuesAverages,
690  const Ice::Current& c)
691  {
692  if (proprioceptionAccumulator.size() != 0)
693  {
694  ARMARX_ERROR << "proprioception accumulator should be empty, when using setting it from raw joint accumulator";
695  }
696 
697  if (rawJointValuesAccumulator.size() % rawJointValuesAverages.size() != 0)
698  {
699  ARMARX_ERROR << "rawJointValuesAverages size is incompatible to accumulator size";
700  }
701 
702  ARMARX_INFO << "rawJointValuesAccumualtor: " << rawJointValuesAccumulator;
703  std::vector<memoryx::KBM::Real> proprioceptionsFromRawJointAccumulator;
704  unsigned int i = 0;
705 
706  for (auto jointValue : rawJointValuesAccumulator)
707  {
708  if (i == rawJointValuesAverages.size())
709  {
710  i = 0;
711  }
712 
713  float offset = rawJointValuesAverages[i];
714  i++;
715 
716  /*
717  * Convert to proprioception
718  */
719  proprioceptionsFromRawJointAccumulator.push_back(jointValue - offset);
720  }
721 
722  ARMARX_INFO << "proprioceptionsFromRawJointAccumulator: " << proprioceptionsFromRawJointAccumulator;
723  proprioceptionAccumulator = proprioceptionsFromRawJointAccumulator;
724 
725  /*
726  * TODO: move to separate method
727  */
728  }
729 
730  void KBMComponent::setPositionLimits(int nDim, const Ice::Current& c)
731  {
732  Eigen::Map<const memoryx::KBM::Matrix> positions = mapMatrix(nDim, positionAccumulator);
733  minima = positions.rowwise().minCoeff();
734  maxima = positions.rowwise().maxCoeff();
735  ARMARX_IMPORTANT << "setting position minima: " << minima.transpose();
736  ARMARX_IMPORTANT << "setting position maxima: " << maxima.transpose();
737  }
738 
739  void KBMComponent::onlineAccumulator(const std::string& name,
740  Ice::Float learningRate,
741  const Ice::Current& c)
742  {
743  online(name, proprioceptionAccumulator, positionAccumulator, learningRate, c);
744  }
745 
746  void KBMComponent::onlineAccumulatorVerbose(const std::string& name,
747  Ice::Float learningRate,
748  const Ice::Current& c)
749  {
750  onlineVerbose(name, proprioceptionAccumulator, positionAccumulator, learningRate, evaluationProprioceptionAccumulator, evaluationPositionAccumulator, c);
751  }
752 
753  void KBMComponent::batchAccumulator(const std::string& name,
754  Ice::Int method,
755  Ice::Float threshold,
756  const Ice::Current& c)
757  {
758  batch(name, proprioceptionAccumulator, positionAccumulator, method, threshold, c);
759  }
760 
761  void KBMComponent::printErrorsAccumulator(const std::string& name, const Ice::Current& c)
762  {
763  printErrors(name, proprioceptionAccumulator, positionAccumulator, c);
764  }
765 
766  void KBMComponent::predictAccumulator(const std::string& name, const Ice::Current& c)
767  {
768  predict(name, proprioceptionAccumulator, c);
769  }
770 
771  /*
772  *
773  *
774  * The following methods should alredady have orientation support
775  *
776  *
777  */
778 
779  void KBMComponent::accumulatePositions(const std::vector<memoryx::KBM::Real>& position, const Ice::Current& c)
780  {
781  /*
782  * accumulate positions
783  */
784  positionAccumulator.insert(positionAccumulator.end(), position.begin(), position.end());
785 
786  //ARMARX_VERBOSE << "Positions Accumulator: " << positionAccumulator;
787  }
788 
789  void KBMComponent::accumulateProprioceptions(const std::vector<memoryx::KBM::Real>& proprioception, const Ice::Current& c)
790  {
791  /*
792  * accumulate proprioceptions
793  */
794  proprioceptionAccumulator.insert(proprioceptionAccumulator.end(), proprioception.begin(), proprioception.end());
795 
796  //ARMARX_VERBOSE << "Proprioception Accumulator: " << proprioceptionAccumulator;
797  }
798 
799  void KBMComponent::accumulateRawJointValues(const std::vector<memoryx::KBM::Real>& rawJointValuesSequence, const Ice::Current& c)
800  {
801  /*
802  * accumulate raw joint values
803  */
804  rawJointValuesAccumulator.insert(rawJointValuesAccumulator.end(), rawJointValuesSequence.begin(), rawJointValuesSequence.end());
805 
806  //ARMARX_VERBOSE << "Raw Joint Values Accumulator: " << rawJointValuesAccumulator;
807  }
808 
809  void KBMComponent::accumulateEvaluationPositions(const std::vector<memoryx::KBM::Real>& position, const Ice::Current& c)
810  {
811  /*
812  * accumulate positions
813  */
814  evaluationPositionAccumulator.insert(evaluationPositionAccumulator.end(), position.begin(), position.end());
815 
816  //ARMARX_VERBOSE << "Positions Accumulator: " << positionAccumulator;
817  }
818 
819  void KBMComponent::accumulateEvaluationProprioceptions(const std::vector<memoryx::KBM::Real>& proprioception, const Ice::Current& c)
820  {
821  /*
822  * accumulate proprioceptions
823  */
824  evaluationProprioceptionAccumulator.insert(evaluationProprioceptionAccumulator.end(), proprioception.begin(), proprioception.end());
825 
826  //ARMARX_VERBOSE << "Proprioception Accumulator: " << proprioceptionAccumulator;
827  }
828 
829  std::vector<memoryx::KBM::Real> KBMComponent::solveGlobalIK(const std::string& name,
830  const std::vector<memoryx::KBM::Real>& targetPosition,
831  const Ice::Current& c)
832  {
833  /*
834  * Check input variables
835  */
837 
838  if (!kbm)
839  {
840  ARMARX_WARNING << "returning empty solution";
841  return std::vector<memoryx::KBM::Real>();
842  }
843 
844  Eigen::Map<const memoryx::KBM::Vector> target(mapPosition(*kbm, targetPosition));
845 
846  /*
847  * Create output variables
848  */
849  std::vector<memoryx::KBM::Real> result(kbm->getNDoF());
850  Eigen::Map<memoryx::KBM::Vector> solution(result.data(), kbm->getNDoF());
851 
852  /*
853  * Solve Global IK
854  */
856  ARMARX_IMPORTANT << "Global IK found " << solutions.size() << " solutions";
857 
858  for (unsigned int i = 0; i < solutions.size(); ++i)
859  {
860  memoryx::KBM::Inverse::Solution solution = solutions[i];
861  ARMARX_IMPORTANT << i << ". solution: " << solution.spreadAngles;
862  }
863 
864  // TODO: support VirtualRobot KBMs by switching proprioceptions
865  if (createdFromVirtualRobot[name])
866  {
867  ARMARX_ERROR << "solveGlobalIK does not yet support KBMs created from Virtual Robot!";
868  }
869 
870  return result; // TODO: currently always 0
871  }
872 
873  std::vector<memoryx::KBM::Real> KBMComponent::solveDifferentialIK(const std::string& name,
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)
880  {
881  /*
882  * Check input variables
883  */
885 
886  if (!kbm)
887  {
888  ARMARX_WARNING << "returning empty solution";
889  return std::vector<memoryx::KBM::Real>();
890  }
891 
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));
897 
898  /*
899  * Check position limits
900  */
901  if (minima.size() != target.size())
902  {
903  ARMARX_ERROR << "minima and target have different size";
904  return std::vector<memoryx::KBM::Real>();
905  }
906 
907  if (maxima.size() != target.size())
908  {
909 
910  ARMARX_ERROR << "maxima and target have different size";
911  return std::vector<memoryx::KBM::Real>();
912  }
913 
914  for (int i = 0; i < kbm->getNDim(); i++)
915  {
916  if (target[i] < minima[i] - 90)
917  {
918  ARMARX_ERROR << "target[" << i << "] = " << target[i] << " is smaller than minima " << minima[i];
919  return std::vector<memoryx::KBM::Real>();
920  }
921 
922  if (target[i] > maxima[i] + 90)
923  {
924  ARMARX_ERROR << "target[" << i << "] = " << target[i] << " is greater than maxima " << maxima[i];
925  return std::vector<memoryx::KBM::Real>();
926  }
927  }
928 
929  /*
930  * Create output variables
931  */
932  std::vector<memoryx::KBM::Real> result(kbm->getNDoF());
933  Eigen::Map<memoryx::KBM::Vector> solution(result.data(), kbm->getNDoF());
934 
935  /*
936  * Solve Differential IK
937  */
938  bool solved;
939 
940  if (createdFromVirtualRobot[name])
941  {
942  /*
943  * support VirtualRobot KBMs by reversing joint order
944  */
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);
947  }
948  else
949  {
950  solved = KBMDifferentialIK::solveMany(*kbm, target, current, proprioception, lowerProprioceptionLimits, upperProprioceptionLimits, solution);
951  }
952 
953  if (createdFromVirtualRobot[name])
954  {
955  /*
956  * support VirtualRobot KBMs by reversing joint order
957  */
958  ARMARX_IMPORTANT << "solution before reverse: " << solution.transpose();
959  solution = solution.colwise().reverse();
960  ARMARX_IMPORTANT << "solution after reverse: " << solution.transpose();
961  }
962 
963  /*
964  * Output
965  */
966  ARMARX_IMPORTANT << "solved = " << solved;
967  ARMARX_IMPORTANT << "solution = " << solution;
968  ARMARX_IMPORTANT << "result (check if equal to solution!) = " << result;
969 
970  return result;
971  }
972 
973 
974  /*
975  *
976  *
977  * KBM Differential Inverse Kinematics
978  *
979  *
980  */
981 
982  float KBMDifferentialIK::randomFloat(float LO, float HI)
983  {
984  return LO + static_cast <float>(rand()) / (static_cast <float>(RAND_MAX / (HI - LO)));
985  }
986 
988  const memoryx::KBM::Models::KBM& kbm,
990  const memoryx::KBM::Vector& position,
991  const memoryx::KBM::Vector& proprioception,
992  float stepSizeFactor,
993  float maxStepSize)
994  {
995 
996  /*
997  * Calculate postion deltas
998  */
999  memoryx::KBM::Vector positionDeltas = stepSizeFactor * (target - position);
1000 
1001  if (positionDeltas.norm() > maxStepSize)
1002  {
1003  positionDeltas *= maxStepSize / positionDeltas.norm();
1004  }
1005 
1006  /*
1007  * Calcualte the jacobian matrix
1008  */
1009  memoryx::KBM::Matrix jacobian = kbm.getJacobian(proprioception);
1010 
1011  /*
1012  * Calculate pseudo inverse using function from simox
1013  * simox uses an algorithm that is numerically stable
1014  */
1015 #ifdef KBM_USE_DOUBLE_PRECISION
1016  memoryx::KBM::Matrix pseudoInverse = VirtualRobot::MathTools::getPseudoInverseD(jacobian);
1017 #else
1018  memoryx::KBM::Matrix pseudoInverse = VirtualRobot::MathTools::getPseudoInverse(jacobian);
1019 #endif
1020 
1021  /*
1022  * Calculate joint deltas
1023  */
1024  memoryx::KBM::Vector jointDeltas = pseudoInverse * positionDeltas;
1025  return jointDeltas;
1026  }
1027 
1029  const memoryx::KBM::Vector& lowerProprioceptionLimits,
1030  const memoryx::KBM::Vector& upperProprioceptionLimits)
1031  {
1032  if (lowerProprioceptionLimits.size() != upperProprioceptionLimits.size())
1033  {
1034  ARMARX_ERROR_S << "limits must have same length";
1035  }
1036 
1037  int n = lowerProprioceptionLimits.size();
1038  memoryx::KBM::Vector result(n);
1039 
1040  for (int i = 0; i < n; i++)
1041  {
1042  float l = lowerProprioceptionLimits(i);
1043  float u = upperProprioceptionLimits(i);
1044  result(i) = randomFloat(l, u);
1045  }
1046 
1047  return result;
1048  }
1049 
1051  const memoryx::KBM::Vector& solution,
1052  const memoryx::KBM::Vector& lowerProprioceptionLimits,
1053  const memoryx::KBM::Vector& upperProprioceptionLimits)
1054  {
1055  /*
1056  * Check parameters
1057  */
1058  int n = solution.size();
1059 
1060  if (lowerProprioceptionLimits.size() != n)
1061  {
1062  ARMARX_ERROR_S << "lower proprioception limits have wrong length: " << lowerProprioceptionLimits.size() << ", should be " << n;
1063  }
1064 
1065  if (upperProprioceptionLimits.size() != n)
1066  {
1067  ARMARX_ERROR_S << "upper proprioception limits have wrong length: " << upperProprioceptionLimits.size() << ", should be " << n;
1068  }
1069 
1070  /*
1071  * Check limits
1072  */
1073  for (int i = 0; i < n; i++)
1074  {
1075  if ((solution(i) < lowerProprioceptionLimits(i)) || (solution(i) > upperProprioceptionLimits(i)))
1076  {
1077  return false;
1078  }
1079  }
1080 
1081  return true;
1082  }
1083 
1085  Eigen::Map<memoryx::KBM::Vector>& solution,
1086  const memoryx::KBM::Vector& lowerProprioceptionLimits,
1087  const memoryx::KBM::Vector& upperProprioceptionLimits)
1088  {
1089  /*
1090  * Check parameters
1091  */
1092  int n = solution.size();
1093 
1094  if (lowerProprioceptionLimits.size() != n)
1095  {
1096  ARMARX_ERROR_S << "lower proprioception limits have wrong length: " << lowerProprioceptionLimits.size() << ", should be " << n;
1097  }
1098 
1099  if (upperProprioceptionLimits.size() != n)
1100  {
1101  ARMARX_ERROR_S << "upper proprioception limits have wrong length: " << upperProprioceptionLimits.size() << ", should be " << n;
1102  }
1103 
1104  /*
1105  * Check limits
1106  */
1107  bool inLimits = true;
1108 
1109  for (int i = 0; i < n; i++)
1110  {
1111  if (solution(i) < lowerProprioceptionLimits(i))
1112  {
1113  solution(i) = lowerProprioceptionLimits(i);
1114  inLimits = false;
1115  }
1116 
1117  if (solution(i) > upperProprioceptionLimits(i))
1118  {
1119  solution(i) = upperProprioceptionLimits(i);
1120  inLimits = false;
1121  }
1122  }
1123 
1124  return inLimits;
1125  }
1126 
1128  const memoryx::KBM::Vector& targetPosition,
1129  const memoryx::KBM::Vector& currentPosition,
1130  const memoryx::KBM::Vector& currentProprioception,
1131  const memoryx::KBM::Vector& lowerProprioceptionLimits,
1132  const memoryx::KBM::Vector& upperProprioceptionLimits,
1133  Eigen::Map<memoryx::KBM::Vector>& solution,
1134  bool applyLimits,
1135  int maxSolves,
1136  float positionTolerance,
1137  float minimumDelta,
1138  bool requireImprovment,
1139  int maxSteps,
1140  float stepSizeFactor,
1141  float maxStepSize)
1142  {
1143 
1144  float bestDistance = FLT_MAX;
1145  bool inLimits = false;
1146 
1147  std::vector<memoryx::KBM::Real> newSolutionSequence(kbm.getNDoF());
1148  Eigen::Map<memoryx::KBM::Vector> newSolution(newSolutionSequence.data(), kbm.getNDoF());
1149 
1150  for (int i = 0; i < maxSolves; i++)
1151  {
1152  memoryx::KBM::Vector startProprioception;
1153 
1154  if (i == 0)
1155  {
1156  startProprioception = currentProprioception;
1157  }
1158  else
1159  {
1160  startProprioception = randomProprioception(lowerProprioceptionLimits, upperProprioceptionLimits);
1161  }
1162 
1163  ARMARX_IMPORTANT_S << "iteration " << (i + 1) << " proprioception: " << startProprioception.transpose();
1164  memoryx::KBM::Vector startPosition = kbm.predict(startProprioception);
1165 
1166  /*
1167  * TODO: it's probably much more efficient, to use the limits
1168  * in the solve method itself and consider the limits right away.
1169  */
1170  KBMDifferentialIK::solve(kbm, targetPosition, startPosition, startProprioception, newSolution, positionTolerance, minimumDelta, requireImprovment, maxSteps, stepSizeFactor, maxStepSize);
1171 
1172  /*
1173  * When using applyLimits, all solutions will be in limits, but solutions
1174  * that were outside the limits will probably get worse.
1175  *
1176  * Note: when using this option, the following limits check and solution ignoring
1177  * doesn't have any effect.
1178  */
1179  if (applyLimits)
1180  {
1181  /*
1182  * distance before enforcing limits
1183  */
1184  memoryx::KBM::Vector testPosition = kbm.predict(newSolution);
1185  float distance = (targetPosition - testPosition).norm();
1186  ARMARX_INFO_S << "distance before enforcing limits: " << distance;
1187 
1188  /*
1189  * modify the solution to be within the limits
1190  */
1191  ARMARX_VERBOSE_S << "solution before apply limits: " << newSolution;
1192  bool wasInLimits = applyProprioceptionLimits(newSolution, lowerProprioceptionLimits, upperProprioceptionLimits);
1193  ARMARX_VERBOSE_S << "solution after apply limits: " << newSolution;
1194 
1195  if (!wasInLimits)
1196  {
1197  ARMARX_IMPORTANT_S << "solution was not within limits, but enforced limits so now it is";
1198  }
1199 
1200  /*
1201  * distance after enforcing limits
1202  */
1203  testPosition = kbm.predict(newSolution);
1204  distance = (targetPosition - testPosition).norm();
1205  ARMARX_INFO_S << "distance after enforcing limits: " << distance;
1206  }
1207 
1208  /*
1209  * If we already found a solution in joint limits,
1210  * only accept other solutions in joint limits.
1211  */
1212  bool currentInLimits = checkProprioceptionLimits(newSolution, lowerProprioceptionLimits, upperProprioceptionLimits);
1213  ARMARX_INFO_S << "is in limits: " << currentInLimits;
1214 
1215  if (applyLimits && !currentInLimits)
1216  {
1217  ARMARX_ERROR_S << "this should not be possible";
1218  ARMARX_ERROR_S << "problematic solution: " << newSolution;
1219  ARMARX_ERROR_S << "lower proprioception limits: " << lowerProprioceptionLimits;
1220  ARMARX_ERROR_S << "upper proprioception limits: " << upperProprioceptionLimits;
1221  }
1222 
1223  if (inLimits && !currentInLimits)
1224  {
1225  ARMARX_IMPORTANT_S << "ignoring solution because we already found one that is within the limits";
1226  continue;
1227  }
1228 
1229  memoryx::KBM::Vector newPosition = kbm.predict(newSolution);
1230  float distance = (targetPosition - newPosition).norm();
1231 
1232  ARMARX_INFO_S << "distance to target: " << distance << ", best known distance " << bestDistance;
1233 
1234  if ((distance < bestDistance) || (currentInLimits && !inLimits))
1235  {
1236  bestDistance = distance;
1237  inLimits = currentInLimits;
1238  solution = newSolution;
1239  ARMARX_IMPORTANT_S << "found new solution: " << solution.transpose();
1240 
1241  if (inLimits && (bestDistance < positionTolerance))
1242  {
1243  ARMARX_IMPORTANT_S << "found a solution within the limits with small distance, aborting search";
1244  break;
1245  }
1246  }
1247  }
1248 
1249  ARMARX_IMPORTANT_S << "final distance: " << bestDistance << ", in limits: " << inLimits;
1250 
1251  if (bestDistance < positionTolerance)
1252  {
1253  return true;
1254  }
1255  else
1256  {
1257  return false;
1258  }
1259  }
1260 
1262  const memoryx::KBM::Vector& targetPosition,
1263  const memoryx::KBM::Vector& currentPosition,
1264  const memoryx::KBM::Vector& currentProprioception,
1265  Eigen::Map<memoryx::KBM::Vector>& solution,
1266  float positionTolerance,
1267  float minimumDelta,
1268  bool requireImprovment,
1269  int maxSteps,
1270  float stepSizeFactor,
1271  float maxStepSize)
1272  {
1273 
1274  assert(targetPosition.size() == kbm.getNDim());
1275  assert(currentPosition.size() == kbm.getNDim());
1276  assert(currentProprioception.size() == kbm.getNDoF());
1277  assert(solution.size() == kbm.getNDoF());
1278 
1279  /*
1280  * In the beginning, our best guess it the current proprioception
1281  */
1282  solution = currentProprioception;
1283 
1284  /*
1285  * The best known distance
1286  */
1287  float bestDistance = (targetPosition - currentPosition).norm();
1288 
1289  /*
1290  * Check if the initial position is already a solution
1291  */
1292  if (bestDistance <= positionTolerance)
1293  {
1294  return true;
1295  }
1296 
1297  /*
1298  * Current joint values
1299  */
1300  memoryx::KBM::Vector simulatedProprioception(currentProprioception);
1301 
1302  /*
1303  * Current position
1304  */
1305  memoryx::KBM::Vector predictedPosition(currentPosition);
1306 
1307  /*
1308  * Compare this to the predicted position
1309  */
1310  ARMARX_IMPORTANT_S << "current predicted position: " << kbm.predict(currentProprioception);
1311 
1312  for (int step = 0; step < maxSteps; ++step)
1313  {
1314  /*
1315  * Calculate joint deltas
1316  */
1317  memoryx::KBM::Vector deltas = calculateJointDeltas(kbm, targetPosition, predictedPosition, simulatedProprioception, stepSizeFactor, maxStepSize);
1318 
1319  /*
1320  * Calculate new joint values
1321  */
1322  simulatedProprioception += deltas;
1323 
1324  /*
1325  * Predict new position
1326  */
1327  predictedPosition = kbm.predict(simulatedProprioception);
1328  ARMARX_IMPORTANT_S << "predicted position: " << predictedPosition;
1329 
1330  /*
1331  * Check if the predicted position is a solution
1332  */
1333  float distance = (targetPosition - predictedPosition).norm();
1334  ARMARX_IMPORTANT_S << "distance to target: " << distance;
1335 
1336  if (distance <= positionTolerance)
1337  {
1338  solution = simulatedProprioception;
1339  return true;
1340  }
1341 
1342  /*
1343  * Stop calculation if result doesn't get better in each iteration
1344  */
1345  if (requireImprovment && (distance >= bestDistance))
1346  {
1347  return false;
1348  }
1349 
1350  /*
1351  * If the new solution is better than the best known solution,
1352  * set it as the new solution!
1353  */
1354  if (distance < bestDistance)
1355  {
1356  solution = simulatedProprioception;
1357  bestDistance = distance;
1358  }
1359 
1360  /*
1361  * Stop calculation if deltas are small
1362  */
1363  if (deltas.norm() < minimumDelta)
1364  {
1365  return false;
1366  }
1367  }
1368 
1369  return false;
1370  }
1371 
1372  Ice::StringSeq KBMComponent::kbmNames(const Ice::Current& c)
1373  {
1374  std::vector<std::string> kbmKeys;
1375 
1376  for (auto it : kbms)
1377  {
1378  kbmKeys.push_back(it.first);
1379  }
1380 
1381  return kbmKeys;
1382  }
1383 
1384  void KBMComponent::clearAccumulators(const Ice::Current& c)
1385  {
1386  positionAccumulator.clear();
1387  proprioceptionAccumulator.clear();
1388  rawJointValuesAccumulator.clear();
1389  }
1390 
1391  void KBMComponent::storeToMemory(const std::string& kbmName, const std::string& nodeSetName, const std::string& referenceFrameName, const std::string& robotName, const Ice::Current& c)
1392  {
1393  memoryx::KBM::Models::KBM_ptr kbm = kbms[kbmName];
1394  if (kbm)
1395  {
1396  // get KBM segment from longterm memory
1397  auto kbmSeg = this->longtermMemoryPrx->getKBMSegment();
1398 
1399  if (kbmSeg)
1400  {
1401  memoryx::KBMDataPtr kbmData = memoryx::KBMDataPtr(new memoryx::KBMData(new armarx::MatrixVariant(kbm->getControlNet()), nodeSetName, referenceFrameName, robotName));
1402  kbmSeg->addEntity(kbmData);
1403  }
1404  }
1405  else
1406  {
1407  ARMARX_WARNING << "Could not store KBM! No KBM segment in longterm memory!";
1408  }
1409 
1410  return;
1411  }
1412 
1413 
1414  void KBMComponent::restoreFromMemory(const std::string& kbmName, const std::string& nodeSetName, const std::string& referenceFrameName, const std::string& robotName, const Ice::Current& c)
1415  {
1416 
1417  auto kbmSeg = this->longtermMemoryPrx->getKBMSegment();
1418  std::string kbmEntityName = robotName + "_" + referenceFrameName + "_" + nodeSetName;
1419 
1420  if (kbmSeg && kbmSeg->hasEntityByName(kbmEntityName))
1421  {
1422  auto entity = kbmSeg->getEntityByName(kbmEntityName);
1423  memoryx::KBMDataPtr kbmData = memoryx::KBMDataPtr::dynamicCast(entity);
1424 
1425  if (kbmData)
1426  {
1427  VirtualRobot::RobotPtr robot = armarx::RemoteRobot::createLocalClone(this->robotStateComponentPrx);
1428  int nDoF = robot->getRobotNodeSet(nodeSetName)->getSize();
1429 
1430  armarx::MatrixVariantPtr controlNet = armarx::MatrixVariantPtr::dynamicCast(kbmData->getControlNet());
1431 
1432  kbms[kbmName] = memoryx::KBM::Models::KBM::createKBM(nDoF, controlNet->rows, Eigen::VectorXd::Zero(nDoF), Eigen::VectorXd::Constant(nDoF, M_PI / 4.0f), controlNet->toEigen().cast<double>());
1433  createdFromVirtualRobot[kbmName] = false; //hacky, because also KBMs created from VirtualRobot could be stored to the longterm memory
1434  }
1435  else
1436  {
1437  ARMARX_WARNING << "Could not restore KBM entity specified by: " << kbmEntityName;
1438  }
1439 
1440 
1441  }
1442 
1443  return;
1444  }
1445 
1446  bool KBMComponent::isInMemory(const std::string& nodeSetName, const std::string& referenceFrameName, const std::string& robotName, const Ice::Current& c)
1447  {
1448  std::string kbmEntityName = robotName + "_" + referenceFrameName + "_" + nodeSetName;
1449 
1450  return (this->longtermMemoryPrx->getKBMSegment() && this->longtermMemoryPrx->getKBMSegment()->hasEntityByName(kbmEntityName));
1451  }
1452 }
1453 
armarx::KBMComponent::createArmar3KBM
void createArmar3KBM(const std::string &name, const Ice::StringSeq &robotNodeNames, const std::vector< memoryx::KBM::Real > &jointValueAverages, const std::vector< memoryx::KBM::Real > &spreadAnglesSequence, const std::string &tcpName, bool useOrientation, const Ice::Current &c=Ice::emptyCurrent) override
createArmar3KBM creates a KBM from a VirtualRobot model
Definition: KBMComponent.cpp:181
RemoteRobot.h
armarx::KBMComponent::onExitComponent
void onExitComponent() override
Definition: KBMComponent.cpp:64
armarx::KBMComponent::getKBM
memoryx::KBM::Models::KBM_ptr getKBM(const std::string &name)
returns a pointer to the KBM with the given name if it exists or a nullptr if it doesn't
Definition: KBMComponent.cpp:135
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
ARMARX_IMPORTANT_S
#define ARMARX_IMPORTANT_S
Definition: Logging.h:203
armarx::KBMComponent::storeToMemory
void storeToMemory(const std::string &, const std::string &, const std::string &, const std::string &, const Ice::Current &) override
Definition: KBMComponent.cpp:1391
armarx::MatrixDouble
The MatrixDouble class.
Definition: MatrixVariant.h:114
armarx::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:918
memoryx::KBM::Models::KBM_ptr
std::shared_ptr< KBM > KBM_ptr
Definition: kbm.h:68
memoryx::KBM::Models::KBM::predict
Matrix predict(const Matrix &proprioception, int dim=0) const
Predicts a value of the FK given a set of joint angles.
Definition: kbm.cpp:317
armarx::KBMComponent::accumulateProprioceptions
void accumulateProprioceptions(const std::vector< memoryx::KBM::Real > &proprioceptions, const Ice::Current &c=Ice::emptyCurrent) override
accumualteProprioceptions accumulates proprioceptions
Definition: KBMComponent.cpp:789
memoryx::KBMDataPtr
IceInternal::Handle< KBMData > KBMDataPtr
Definition: KBMData.h:71
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
memoryx::KBM::Models::KBM::getNDim
int getNDim() const
Definition: kbm.cpp:397
memoryx::KBM::Matrix
Eigen::MatrixXd Matrix
Definition: kbm.h:38
armarx::KBMDifferentialIK::solve
bool solve(const memoryx::KBM::Models::KBM &kbm, const memoryx::KBM::Vector &targetPosition, const memoryx::KBM::Vector &currentPostion, const memoryx::KBM::Vector &currentProprioception, Eigen::Map< memoryx::KBM::Vector > &solution, float positionTolerance=5.0f, float minimumDelta=0.0f, bool requireImprovment=false, int maxSteps=50, float stepSizeFactor=0.2f, float maxStepSize=FLT_MAX)
solves the inverse kinematics
Definition: KBMComponent.cpp:1261
armarx::KBMComponent::onInitComponent
void onInitComponent() override
Definition: KBMComponent.cpp:45
armarx::KBMComponent::onlineVerbose
void onlineVerbose(const std::string &name, const std::vector< memoryx::KBM::Real > &proprioceptionSequence, const std::vector< memoryx::KBM::Real > &positionSequence, Ice::Float learningRate, const std::vector< memoryx::KBM::Real > &evaluationProprioceptionSequence, const std::vector< memoryx::KBM::Real > &evaluationPositionSequence, const Ice::Current &c=Ice::emptyCurrent) override
same as online, but evaluates after each learning iteration
Definition: KBMComponent.cpp:409
armarx::KBMComponent::onlineAccumulatorVerbose
void onlineAccumulatorVerbose(const std::string &name, Ice::Float learningRate, const Ice::Current &c=Ice::emptyCurrent) override
onlineAccumulatorVerbose same as onlineAccumulator, but evaluates after each learning step
Definition: KBMComponent.cpp:746
armarx::KBMComponent::mapProprioceptions
Eigen::Map< const memoryx::KBM::Matrix > mapProprioceptions(const memoryx::KBM::Models::KBM &kbm, const std::vector< memoryx::KBM::Real > &proprioception)
mapProprioceptions converts the proprioception sequence into an Eigen::Map of a Matrix
Definition: KBMComponent.cpp:109
armarx::KBMComponent::batchAccumulator
void batchAccumulator(const std::string &name, Ice::Int method, Ice::Float threshold, const Ice::Current &c=Ice::emptyCurrent) override
the same as batch but with the data from the accumulator
Definition: KBMComponent.cpp:753
memoryx::KBM::Inverse::Solution
Definition: kbm.h:365
armarx::KBMComponent::online
void online(const std::string &name, const std::vector< memoryx::KBM::Real > &proprioceptionSequence, const std::vector< memoryx::KBM::Real > &positionSequence, Ice::Float learningRate, const Ice::Current &c=Ice::emptyCurrent) override
online learning of n training samples
Definition: KBMComponent.cpp:368
armarx::KBMComponent::clearAccumulators
void clearAccumulators(const Ice::Current &c) override
Clears the accumulators.
Definition: KBMComponent.cpp:1384
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:688
memoryx::KBM::Models::KBM::ErrorValuesType::Mean
Real Mean
Mean error.
Definition: kbm.h:109
armarx::KBMDifferentialIK::randomProprioception
memoryx::KBM::Vector randomProprioception(const memoryx::KBM::Vector &lowerProprioceptionLimits, const memoryx::KBM::Vector &upperProprioceptionLimits)
Creates a vector of random values between the limits.
Definition: KBMComponent.cpp:1028
memoryx::KBM::Models::KBM::getJacobian
Matrix getJacobian(const Vector &proprioception) const
Computes the partial derivative with respect to a configuration.
Definition: kbm.cpp:370
armarx::KBMComponent::printAccumulatorStatistics
void printAccumulatorStatistics(int nDim, int nDoF, const Ice::Current &c=Ice::emptyCurrent) override
printAccumulatorStatistics prints information about the values in the accumulators
Definition: KBMComponent.cpp:634
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::KBMComponent::onDisconnectComponent
void onDisconnectComponent() override
Definition: KBMComponent.cpp:59
armarx::KBMComponent::printErrorsAccumulator
void printErrorsAccumulator(const std::string &name, const Ice::Current &c=Ice::emptyCurrent) override
the same as printErrors but with the data from the accumulator
Definition: KBMComponent.cpp:761
armarx::KBMComponent::mapPositions
Eigen::Map< const memoryx::KBM::Matrix > mapPositions(const memoryx::KBM::Models::KBM &kbm, const std::vector< memoryx::KBM::Real > &position)
mapPositions converts the position sequence into an Eigen::Map of a Matrix
Definition: KBMComponent.cpp:96
memoryx::KBM::Vector
Eigen::VectorXd Vector
Definition: kbm.h:39
memoryx::KBM::Models::KBM::ErrorValuesType
Return type of the evaluation (KBM::getErrors()) function providing insight in the statistics of the ...
Definition: kbm.h:106
armarx::KBMComponent::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: KBMComponent.cpp:68
armarx::KBMComponent::getRawJointValuesAverages
Ice::DoubleSeq getRawJointValuesAverages(int nDoF, const Ice::Current &c=Ice::emptyCurrent) override
getRawJointValuesAverages calculates the average raw joint values for each joint from the data stored...
Definition: KBMComponent.cpp:650
armarx::KBMComponent::getSpreadAngles
Ice::DoubleSeq getSpreadAngles(int nDoF, const Ice::Current &c=Ice::emptyCurrent) override
getSpreadAngles returns the spreadAngles calculated using the data in the proprioceptionAccumulator
Definition: KBMComponent.cpp:664
memoryx::KBM::Models::KBM::createFromVirtualRobot
static KBM_ptr createFromVirtualRobot(VirtualRobot::KinematicChainPtr chain, VirtualRobot::SceneObjectPtr FoR, const Vector &spreadAngles, bool useOrientation=false)
Definition: kbm.cpp:440
armarx::KBMComponent::accumulateEvaluationProprioceptions
void accumulateEvaluationProprioceptions(const std::vector< memoryx::KBM::Real > &proprioceptions, const Ice::Current &c=Ice::emptyCurrent) override
accumualteProprioceptions accumulates proprioceptions in the evaluate accumulator
Definition: KBMComponent.cpp:819
IceInternal::Handle
Definition: forward_declarations.h:8
armarx::KBMDifferentialIK::solveMany
bool solveMany(const memoryx::KBM::Models::KBM &kbm, const memoryx::KBM::Vector &targetPosition, const memoryx::KBM::Vector &currentPosition, const memoryx::KBM::Vector &currentProprioception, const memoryx::KBM::Vector &lowerProprioceptionLimits, const memoryx::KBM::Vector &upperProprioceptionLimits, Eigen::Map< memoryx::KBM::Vector > &solution, bool applyLimits=true, int maxSolves=25, float positionTolerance=5.0f, float minimumDelta=0.0f, bool requireImprovment=false, int maxSteps=50, float stepSizeFactor=0.2f, float maxStepSize=FLT_MAX)
KBMDifferentialIK::solveMany runs solve many times.
Definition: KBMComponent.cpp:1127
armarx::KBMComponent::accumulatePositions
void accumulatePositions(const std::vector< memoryx::KBM::Real > &positionSequence, const Ice::Current &c=Ice::emptyCurrent) override
accumulate adds the given position to the accumulator to use it later
Definition: KBMComponent.cpp:779
armarx::KBMComponent::setProprioceptionAccumulatorFromRawJointAccumulator
void setProprioceptionAccumulatorFromRawJointAccumulator(const std::vector< memoryx::KBM::Real > &rawJointValuesAverages, const Ice::Current &c=Ice::emptyCurrent) override
setProprioceptionAccumulatorFromRawJointAccumulator updates the proprioception accumulator
Definition: KBMComponent.cpp:689
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
armarx::KBMComponent::accumulateEvaluationPositions
void accumulateEvaluationPositions(const std::vector< memoryx::KBM::Real > &positionSequence, const Ice::Current &c=Ice::emptyCurrent) override
accumulates the given position in the evaluation accumulator
Definition: KBMComponent.cpp:809
armarx::KBMComponent::batch
void batch(const std::string &name, const std::vector< memoryx::KBM::Real > &proprioceptionSequence, const std::vector< memoryx::KBM::Real > &positionSequence, Ice::Int method, Ice::Float threshold, const Ice::Current &c=Ice::emptyCurrent) override
batch learning of n training samples
Definition: KBMComponent.cpp:327
armarx::KBMComponent::printErrors
void printErrors(const std::string &name, const std::vector< memoryx::KBM::Real > &proprioceptionSequence, const std::vector< memoryx::KBM::Real > &positionSequence, const Ice::Current &c=Ice::emptyCurrent) override
calls getErrors on the KBM and prints the result
Definition: KBMComponent.cpp:591
armarx::KBMComponent::isInMemory
bool isInMemory(const std::string &nodeSetName, const std::string &referenceFrameName, const std::string &robotName, const Ice::Current &c) override
Definition: KBMComponent.cpp:1446
M_PI
#define M_PI
Definition: MathTools.h:17
EntityAttribute.h
memoryx::KBM::Models::KBM::createKBM
static KBM_ptr createKBM(int nDoF, int dim, const Vector &center, const Vector &spreadAngles, const Matrix &controlNet)
Factory methods.
Definition: kbm.cpp:407
armarx::KBMComponent::accumulateRawJointValues
void accumulateRawJointValues(const std::vector< memoryx::KBM::Real > &rawJointValuesSequence, const Ice::Current &c=Ice::emptyCurrent) override
accumualteRawJointValues accumulates raw joint values that will be transformed to proprioceptions lat...
Definition: KBMComponent.cpp:799
memoryx::KBM::Models::KBM::getNDoF
int getNDoF() const
Get the number of degrees of freedom (DoF).
Definition: kbm.cpp:392
armarx::KBMComponent::restoreFromMemory
void restoreFromMemory(const std::string &, const std::string &, const std::string &, const std::string &, const Ice::Current &) override
Definition: KBMComponent.cpp:1414
ARMARX_ERROR_S
#define ARMARX_ERROR_S
Definition: Logging.h:209
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
armarx::KBMDifferentialIK::randomFloat
float randomFloat(float LO, float HI)
randomFloat creates a random float between LO and HI
Definition: KBMComponent.cpp:982
armarx::KBMComponent::mapProprioception
Eigen::Map< const memoryx::KBM::Vector > mapProprioception(const memoryx::KBM::Models::KBM &kbm, const std::vector< memoryx::KBM::Real > &proprioception)
mapProprioception converts the proprioception sequence into an Eigen::Map of a Vector
Definition: KBMComponent.cpp:89
KBMData.h
filename
std::string filename
Definition: VisualizationRobot.cpp:83
armarx::KBMComponentPropertyDefinitions
Definition: KBMComponent.h:49
armarx::KBMComponent::solveGlobalIK
std::vector< memoryx::KBM::Real > solveGlobalIK(const std::string &name, const std::vector< memoryx::KBM::Real > &targetPosition, const Ice::Current &c=Ice::emptyCurrent) override
solveGlobalIK solves the global inverse kinematics for the given position
Definition: KBMComponent.cpp:829
armarx::KBMComponent::setPositionLimits
void setPositionLimits(int nDim, const Ice::Current &c=Ice::emptyCurrent) override
setPositionLimits sets the position limits using the data in the position accumulator
Definition: KBMComponent.cpp:730
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
armarx::KBMComponent::createKBM
void createKBM(const std::string &name, Ice::Int nDoF, Ice::Int dim, Ice::Float spreadAngle, const Ice::Current &c=Ice::emptyCurrent) override
createKBM creates a new KBM and makes it available under the given name
Definition: KBMComponent.cpp:157
memoryx::KBM::Models::KBM::Optimization
Optimization
Enum for the preferred optimization method during batch learning.
Definition: kbm.h:83
armarx::deltas
Definition: BasicControllers.h:57
armarx::KBMDifferentialIK::checkProprioceptionLimits
bool checkProprioceptionLimits(const memoryx::KBM::Vector &solution, const memoryx::KBM::Vector &lowerProprioceptionLimits, const memoryx::KBM::Vector &upperProprioceptionLimits)
check if solution is within the limits
Definition: KBMComponent.cpp:1050
armarx::KBMComponent::onConnectComponent
void onConnectComponent() override
Definition: KBMComponent.cpp:52
memoryx::KBM::Inverse::Solution::spreadAngles
Vector spreadAngles
Definition: kbm.h:371
memoryx::KBM::Inverse::solveGlobalIK
void solveGlobalIK(unsigned int recursion, int side, SolutionSet &solutionSet, Models::KBM_ptr kbm, const Vector &lower, const Vector &upper, Real resolution, Vector spreadAngles, Vector center)
Definition: inverse.cpp:344
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:74
armarx::KBMComponent::mapPosition
Eigen::Map< const memoryx::KBM::Vector > mapPosition(const memoryx::KBM::Models::KBM &kbm, const std::vector< memoryx::KBM::Real > &position)
mapPosition converts the position sequence into an Eigen::Map of a Vector
Definition: KBMComponent.cpp:82
memoryx::KBMData
Definition: KBMData.h:46
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::RemoteRobot::createLocalClone
VirtualRobot::RobotPtr createLocalClone()
Clones the structure of this remote robot to a local instance.
Definition: RemoteRobot.cpp:328
pseudoInverse
Eigen::MatrixXd pseudoInverse(const Eigen::MatrixXd &a, double epsilon=std::numeric_limits< double >::epsilon())
Definition: pinv.hh:6
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::KBMComponent::onlineAccumulator
void onlineAccumulator(const std::string &name, Ice::Float learningRate, const Ice::Current &c=Ice::emptyCurrent) override
onlineAccumulator calls online after transforming the raw joint accumulator to proprioceptions
Definition: KBMComponent.cpp:739
armarx::KBMComponent::kbmNames
Ice::StringSeq kbmNames(const Ice::Current &c) override
Returns the names of the existing KBMs.
Definition: KBMComponent.cpp:1372
memoryx::KBM::Models::KBM
The Kinematic B\'ezier Maps.
Definition: kbm.h:78
armarx::VariantType::Int
const VariantTypeId Int
Definition: Variant.h:916
ARMARX_VERBOSE_S
#define ARMARX_VERBOSE_S
Definition: Logging.h:200
armarx::KBMComponent::predictAccumulator
void predictAccumulator(const std::string &name, const Ice::Current &c=Ice::emptyCurrent) override
the same as predict but with the data from the accumulator, however the results are currently just pr...
Definition: KBMComponent.cpp:766
armarx::KBMComponent::solveDifferentialIK
std::vector< memoryx::KBM::Real > solveDifferentialIK(const std::string &name, const std::vector< memoryx::KBM::Real > &targetPosition, const std::vector< memoryx::KBM::Real > &currentPosition, const std::vector< memoryx::KBM::Real > &proprioceptionSequence, const std::vector< memoryx::KBM::Real > &lowerProprioceptionLimitsSequence, const std::vector< memoryx::KBM::Real > &upperProprioceptionLimitsSequence, const Ice::Current &c=Ice::emptyCurrent) override
solveDifferentialIK solves the differential inverse kinematics for the given position
Definition: KBMComponent.cpp:873
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:88
ARMARX_INFO_S
#define ARMARX_INFO_S
Definition: Logging.h:195
armarx::KBMComponent::mapMatrix
Eigen::Map< const memoryx::KBM::Matrix > mapMatrix(int rows, const std::vector< memoryx::KBM::Real > &data)
maps a sequence to an Eigen::Map
Definition: KBMComponent.cpp:122
KBMComponent.h
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:34
armarx::KBMDifferentialIK::applyProprioceptionLimits
bool applyProprioceptionLimits(Eigen::Map< memoryx::KBM::Vector > &solution, const memoryx::KBM::Vector &lowerProprioceptionLimits, const memoryx::KBM::Vector &upperProprioceptionLimits)
apply limits to solution and return true, if solution has been changed = solution was not in limits
Definition: KBMComponent.cpp:1084
armarx::KBMDifferentialIK::calculateJointDeltas
memoryx::KBM::Vector calculateJointDeltas(const memoryx::KBM::Models::KBM &kbm, const memoryx::KBM::Vector &target, const memoryx::KBM::Vector &position, const memoryx::KBM::Vector &proprioception, float stepSizeFactor, float maxStepSize)
calculateJointDeltas is in internal function called by solve
Definition: KBMComponent.cpp:987
memoryx::KBM::Inverse::SolutionSet
std::vector< Solution > SolutionSet
Return type of the global inverse kinematics solvers.
Definition: kbm.h:378
armarx::ManagedIceObject::usingProxy
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Definition: ManagedIceObject.cpp:151
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::KBMComponent::predict
std::vector< memoryx::KBM::Real > predict(const std::string &name, const std::vector< memoryx::KBM::Real > &proprioceptionSequence, const Ice::Current &c=Ice::emptyCurrent) override
predict the position for n samples of proprioception (forward kinematics)
Definition: KBMComponent.cpp:557
norm
double norm(const Point &a)
Definition: point.hpp:94