MotionModelKBM.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2011-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
19 * @author
20 * @date
21 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22 * GNU General Public License
23 */
24
25#include "MotionModelKBM.h"
26
27#include <VirtualRobot/LinkedCoordinate.h>
28#include <VirtualRobot/Robot.h>
29#include <VirtualRobot/RobotNodeSet.h>
30
32
35
36using namespace VirtualRobot;
37
38namespace memoryx
39{
40 MotionModelKBM::MotionModelKBM(std::string referenceNodeName,
41 std::string nodeSetName,
43 memoryx::LongtermMemoryInterfacePrx longtermMemory) :
44 AbstractMotionModel(robotStateProxy)
45 {
46 this->nodeSetName = nodeSetName;
47 this->referenceNodeName = referenceNodeName;
48
49 this->longtermMemory = longtermMemory;
50 memoryName = robotStateProxy->getRobotName() + "_" + referenceNodeName + "_" + nodeSetName;
52 init();
53 }
54
55 void
57 const armarx::LinkedPoseBasePtr& poseAtLastLocalization,
58 const armarx::PoseBasePtr& globalRobotPoseAtLastLocalization,
59 const MultivariateNormalDistributionBasePtr& uncertaintyAtLastLocalization,
60 const Ice::Current& c)
61 {
62 std::unique_lock lock(motionPredictionLock);
63 this->poseAtLastLocalization = poseAtLastLocalization;
64 timeOfLastSuccessfulLocalization =
65 armarx::TimestampVariantPtr::dynamicCast(timeOfLastLocalizationStart->clone());
66
67 if (globalRobotPoseAtLastLocalization)
68 {
69 this->globalRobotPoseAtLastLocalization = globalRobotPoseAtLastLocalization;
70 }
71
72 if (uncertaintyAtLastLocalization)
73 {
74 this->uncertaintyAtLastLocalization = uncertaintyAtLastLocalization;
75 }
76
77 armarx::LinkedPosePtr pose = armarx::LinkedPosePtr::dynamicCast(poseAtLastLocalization);
78
79 pose->changeFrame(referenceNodeName);
80 auto poseKBM = armarx::LinkedPosePtr::dynamicCast(pose->clone());
81 poseKBM->changeFrame(robot->getRobotNodeSet(nodeSetName)->getKinematicRoot()->getName());
82
83 KBM::Matrix shape = poseKBM->toEigen().block<3, 1>(0, 3).cast<double>();
84 // shape.conservativeResize(3, 1);
85
86 kbm->online(this->getJointAngles(poseAtLastLocalization->referenceRobot).cast<double>(),
87 shape);
88 }
89
92 {
93 std::unique_lock lock(motionPredictionLock);
94 armarx::LinkedPosePtr linkedPose =
95 armarx::LinkedPosePtr::dynamicCast(poseAtLastLocalization);
96
97 //auto snapshot = robotStateProxy->getRobotSnapshot(robotStateProxy->getSynchronizedRobot()->getName());
98
99 auto snapShot = robotStateProxy->getRobotSnapshot(robot->getName());
100 Eigen::MatrixXd jointAngles =
101 this->getJointAngles(snapShot).cast<double>() /*.colwise().reverse().reverse()*/;
102 ARMARX_DEBUG_S << VAROUT(jointAngles);
103 auto time = IceUtil::Time::now();
104 Eigen::Vector3f kbmPos = this->kbm->predict(jointAngles).cast<float>();
105 ARMARX_DEBUG_S << "KBM prediction Took: "
106 << (IceUtil::Time::now() - time).toMilliSecondsDouble() << " ms";
107 auto nodeSet = robot->getRobotNodeSet(nodeSetName);
108 Eigen::Matrix4f pose = nodeSet->getTCP()->getGlobalPose();
109 armarx::FramedPosition framedKbmPos(
110 kbmPos, nodeSet->getKinematicRoot()->getName(), linkedPose->agent);
111 framedKbmPos.changeToGlobal(robot);
112 ARMARX_DEBUG_S << pose.block<3, 1>(0, 3) << " vs. " << framedKbmPos.toEigen();
113 ARMARX_DEBUG_S << "Difference between KBM and robot model: "
114 << (pose.block<3, 1>(0, 3) - framedKbmPos.toEigen()).norm() << " mm";
115 pose.block<3, 1>(0, 3) = framedKbmPos.toEigen();
116 //shape.conservativeResize(4, 4);
117 // FramedPose framedPose(pose, nodeSet->getKinematicRoot()->getName(), linkedPose->agent);
119 return ret;
120 }
121
122 Eigen::MatrixXf
124 {
126 Eigen::MatrixXf proprioception(nDoF, 1);
127 std::vector<float> jointAngles = robot->getRobotNodeSet(nodeSetName)->getJointValues();
128 ARMARX_CHECK_EXPRESSION(nDoF == (int)jointAngles.size());
129 for (int i = 0; i < nDoF; i++)
130 {
131 proprioception(i, 0) = jointAngles[i];
132 }
133
134 return proprioception;
135 }
136
137 void
139 {
140 ARMARX_INFO_S << "KBM Database update";
141
142
143 if (longtermMemory)
144 {
145 auto kbmSeg = longtermMemory->getKBMSegment();
146 std::unique_lock lock(motionPredictionLock);
147
148
149 if (kbmSeg)
150 {
151 if (kbmSeg->hasEntityByName(memoryName))
152 {
153 auto entity = kbmSeg->getEntityByName(memoryName);
154 KBMDataPtr kbmData = KBMDataPtr::dynamicCast(entity);
155
156 if (kbmData)
157 {
158 if (kbm)
159 {
160 kbmData->setControlNet(new armarx::MatrixVariant(kbm->getControlNet()));
161 kbmSeg->updateEntity(kbmData->getId(), kbmData);
162 }
163 else
164 {
165 ARMARX_WARNING_S << "No KBM!";
166 }
167 }
168 else
169 {
170 ARMARX_WARNING_S << "Entity is not KBMData. MemoryName: " << memoryName
171 << " Entity ice_id:" << entity->ice_id();
172 }
173 }
174 else
175 {
176 if (kbm)
177 {
178 KBMDataPtr kbmData =
179 KBMDataPtr(new KBMData(new armarx::MatrixVariant(kbm->getControlNet()),
180 nodeSetName,
181 referenceNodeName,
182 robotStateProxy->getRobotName()));
183 ARMARX_INFO_S << "Adding new kbm with name " << kbmData->getName();
184 kbmSeg->addEntity(kbmData);
185 }
186 else
187 {
188 ARMARX_WARNING_S << "No KBM!";
189 }
190 }
191 }
192 else
193 {
194 ARMARX_WARNING_S << "No KBM Segment!";
195 }
196 }
197 }
198
199 void
200 MotionModelKBM::init()
201 {
202 ARMARX_DEBUG << "init";
203 //armarx::SharedRobotInterfacePrx currentRobotSnapshot = ;//getRobotSnapshot("KBMSnapshot");
205
206 nDoF = robot->getRobotNodeSet(this->nodeSetName)->getSize();
207
208 auto kbmSeg = longtermMemory->getKBMSegment();
209 std::unique_lock lock(motionPredictionLock);
210
212 if (kbmSeg && kbmSeg->hasEntityByName(memoryName))
213 {
214 ARMARX_VERBOSE << "Fetching KBM from memory";
215 auto entity = kbmSeg->getEntityByName(memoryName);
216 KBMDataPtr kbmData = KBMDataPtr::dynamicCast(entity);
217
218 if (kbmData)
219 {
220
221 armarx::MatrixVariantPtr controlNet =
222 armarx::MatrixVariantPtr::dynamicCast(kbmData->getControlNet());
223
224 this->kbm =
226 controlNet->rows,
227 Eigen::VectorXd::Zero(nDoF),
228 Eigen::VectorXd::Constant(nDoF, M_PI / 4.0f),
229 controlNet->toEigen().cast<double>());
230 }
231 else
232 {
233 ARMARX_WARNING_S << "Entity is not KBMData. MemoryName: " << memoryName
234 << " Entity ice_id:" << entity->ice_id();
235 }
236
237 // get file from long-term memory and store in name in
238 //std::string tempFileName;
239 //this->kbm.reset(new KBM::Models::KBM(nDoF,16,M_PI/4.0f));
240 //this->kbm->restore(tempFileName);
241 }
242 else
243 {
244 // If longtermmemory = empty
245 ARMARX_VERBOSE << "Longterm memory empty";
246
247 try
248 {
249
250 auto nodeSet = robot->getRobotNodeSet(nodeSetName);
251 this->kbm = CreateKBMFromSamples(robot, nodeSet, nodeSet->getKinematicRoot());
252 KBMDataPtr kbmData = new KBMData(new armarx::MatrixDouble(kbm->getControlNet()),
253 nodeSetName,
254 referenceNodeName,
255 robot->getName());
256 kbmSeg->addEntity(kbmData);
257 ARMARX_VERBOSE << "Adding new entity with name " << kbmData->getName();
258 // this->kbm = KBM::Models::KBM::createFromVirtualRobot(chain, FoR, Eigen::VectorXd::Constant(nDoF, M_PI / 4.0), false);
259 }
260 catch (VirtualRobot::VirtualRobotException& e)
261 {
262 ARMARX_ERROR_S << "KBM creation exception. " << e.what();
263
264 /*
265 * Probably an invalid Kinematic chain.
266 * Throw an adequate exception here!
267 */
268 }
269 }
270
271
273
274 if (longtermMemory)
275 {
276 updaterThreadTask = new armarx::PeriodicTask<MotionModelKBM>(
277 this, &MotionModelKBM::periodicUpdate, 1000 * 60);
278 updaterThreadTask->start();
279 }
280 }
281
284 VirtualRobot::RobotNodeSetPtr nodeSet,
285 VirtualRobot::SceneObjectPtr referenceFrame)
286 {
287 ARMARX_INFO_S << "Starting to generate KBM with random samples for nodeset "
288 << nodeSet->getName();
289 nodeSet->print();
291 // KBMComponentInterfacePrx kbmComponent = getKbmComponent();
292 std::vector<RobotNodePtr> nodes = nodeSet->getAllRobotNodes();
293 RobotNodePtr root = nodeSet->getKinematicRoot();
294 RobotNodePtr TCP = nodeSet->getTCP();
295 size_t nJoints = nodes.size();
296 size_t nOutputDim = 3;
297 Eigen::VectorXf jointMin = Eigen::VectorXf::Zero(nJoints, 1);
298 Eigen::VectorXf jointMax = Eigen::VectorXf::Zero(nJoints, 1);
299
300 for (size_t i = 0; i < nJoints; i++)
301 {
302 RobotNodePtr n = nodes[i];
303 jointMax(i) = n->getJointLimitHi() - 0.1f;
304 jointMin(i) = n->getJointLimitLo() + 0.1f;
305 }
306
307 // if(kbmComponent->isInMemory(in.getnodeSetName(),root->getName(),robot->getName()))
308 // {
309 // ARMARX_INFO << "Loading KBM from memory";
310 // kbmComponent->restoreFromMemory(in.getkbmName(),in.getnodeSetName(),root->getName(), robot->getName());
311 // }
312 // else
313 // {
314 // ARMARX_INFO << "KBM not found in memory. Batch training KBM.";
315
316 size_t nTrainingSamples = (size_t)pow(nOutputDim, nJoints);
317 kbm.reset(new memoryx::KBM::Models::KBM(nJoints, nOutputDim, M_PI / 4.0f));
318 std::vector<memoryx::KBM::Real> proprioceptionAccumulator;
319 std::vector<memoryx::KBM::Real> positionAccumulator;
320 ARMARX_INFO_S << VAROUT(nTrainingSamples);
321 for (size_t i = 0; i < nTrainingSamples; i++)
322 {
323 Ice::DoubleSeq proprioception, pos;
324
325 CreateSample(nodeSet, jointMax, jointMin, root, TCP, proprioception, pos);
326
327 proprioceptionAccumulator.insert(
328 proprioceptionAccumulator.end(), proprioception.begin(), proprioception.end());
329 positionAccumulator.insert(positionAccumulator.end(), pos.begin(), pos.end());
330 }
331 auto mapVectorToMatrix = [](const std::vector<memoryx::KBM::Real>& vec, size_t rows)
332 {
333 size_t cols = vec.size() / rows;
334 return Eigen::Map<const memoryx::KBM::Matrix>(vec.data(), rows, cols);
335 };
336
337 kbm->batch(mapVectorToMatrix(proprioceptionAccumulator, nJoints),
338 mapVectorToMatrix(positionAccumulator, nOutputDim),
340 0.0f);
341 // kbmComponent->createKBM(in.getkbmName(), nJoints, 3, M_PI/4.0f);
342 // kbmComponent->batchAccumulator(in.getkbmName(),0,0.0f);
343 // kbmComponent->storeToMemory(in.getkbmName(),in.getnodeSetName(),root->getName(), robot->getName());
344
345 // kbmComponent->printAccumulatorStatistics(3, nJoints);
346 // kbmComponent->printErrorsAccumulator(in.getkbmName());
347 // kbmComponent->clearAccumulators();
348 // }
349
350
351 // unsigned int nEvaluationSamples = (int)pow(nOutputDim, nJoints) / 20;
352 // proprioceptionAccumulator.clear();
353 // positionAccumulator.clear();
354 // for (size_t i = 0; i < nEvaluationSamples; i++)
355 // {
356 // Ice::DoubleSeq prop, pos;
357
358 // CreateSample(nodeSet, jointMax, jointMin, root, TCP, prop, pos);
359 // proprioceptionAccumulator.insert(proprioceptionAccumulator.end(), prop.begin(), prop.end());
360 // positionAccumulator.insert(positionAccumulator.end(), pos.begin(), pos.end());
361 // ARMARX_INFO_S << "Error: " << (kbm->predict(mapVectorToMatrix(prop, nJoints)) - mapVectorToMatrix(pos, nOutputDim)).norm() << " mm";
362 // }
363 // auto errors = kbm->getErrors(mapVectorToMatrix(proprioceptionAccumulator, nJoints),
364 // mapVectorToMatrix(positionAccumulator, nOutputDim));
365 // ARMARX_INFO_S << "Errors: " << errors;
366 ARMARX_INFO_S << "DONE";
367
368 return kbm;
369 }
370
371 memoryx::MultivariateNormalDistributionBasePtr
373 {
374 if (uncertaintyAtLastLocalization)
375 {
376 auto handNodeName = robot->getRobotNodeSet(nodeSetName)->getTCP()->getName();
377 armarx::PosePtr oldHandNodePose = armarx::PosePtr::dynamicCast(
378 poseAtLastLocalization->referenceRobot->getRobotNode(handNodeName)
379 ->getPoseInRootFrame());
380 armarx::PosePtr newHandNodePose =
381 armarx::PosePtr::dynamicCast(robotStateProxy->getSynchronizedRobot()
382 ->getRobotNode(handNodeName)
383 ->getPoseInRootFrame());
384
385 // additional uncertainty is 0.07 * the distance that the hand moved since the last localization
386 float dist = (oldHandNodePose->toEigen().block<3, 1>(0, 3) -
387 newHandNodePose->toEigen().block<3, 1>(0, 3))
388 .norm();
389 dist *= 0.3;
390 Eigen::Matrix3f additionalUncertainty = dist * dist * Eigen::Matrix3f::Identity();
391
392 Eigen::Matrix3f oldUncertainty =
393 MultivariateNormalDistributionPtr::dynamicCast(uncertaintyAtLastLocalization)
394 ->toEigenCovariance();
395 Eigen::Matrix3f newUncertainty = oldUncertainty + additionalUncertainty;
396
398 armarx::Vector3Ptr::dynamicCast(poseAtLastLocalization->position)->toEigen(),
399 newUncertainty);
400 }
401 else
402 {
403 return NULL;
404 }
405 }
406
407 void
409 {
410 init();
411 }
412
413 void
414 MotionModelKBM::CreateSample(RobotNodeSetPtr nodeSet,
415 Eigen::VectorXf jointMax,
416 Eigen::VectorXf jointMin,
417 RobotNodePtr root,
418 RobotNodePtr TCP,
419 Ice::DoubleSeq& prop,
420 Ice::DoubleSeq& shape)
421 {
422 unsigned int nJoints = nodeSet->getSize();
423 Eigen::VectorXf rnd = Eigen::VectorXf::Random(nJoints, 1);
424 Eigen::VectorXf sample =
425 (rnd + Eigen::VectorXf::Ones(nJoints, 1)).cwiseProduct((jointMax - jointMin) / 2) +
426 jointMin;
427
428 for (size_t k = 0; k < nJoints; k++)
429 {
430 nodeSet->getNode(k)->setJointValue(sample(k));
431 }
432 std::vector<float> actualJointValues = nodeSet->getJointValues();
433 // for (size_t l = 0; l < nJoints; l++)
434 // {
435 // actualJointValues.push_back(nodeSet->getNode(l)->getJointValue());
436 // }
437
438 Eigen::Vector3f tcpPos = TCP->getTransformationFrom(root).block<3, 1>(0, 3);
439
440 for (size_t j = 0; j < nJoints; j++)
441 {
442 prop.push_back(actualJointValues[j]);
443 }
444
445 assert(tcpPos.rows() >= 0);
446 for (size_t k = 0; k < static_cast<std::size_t>(tcpPos.rows()); k++)
447 {
448 shape.push_back(tcpPos(k));
449 }
450 }
451
452
453} // namespace memoryx
#define M_PI
Definition MathTools.h:17
#define VAROUT(x)
constexpr T c
The FramedPosition class.
Definition FramedPose.h:158
void changeToGlobal(const SharedRobotInterfacePrx &referenceRobot)
The LinkedPose class.
Definition LinkedPose.h:61
static VirtualRobot::RobotPtr createLocalCloneFromFile(RobotStateComponentInterfacePrx robotStatePrx, VirtualRobot::RobotIO::RobotDescription loadMode=VirtualRobot::RobotIO::eFull)
This is a convenience function for createLocalClone, which automatically gets the filename from the R...
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
virtual Eigen::Vector3f toEigen() const
Definition Pose.cpp:134
std::recursive_mutex motionPredictionLock
AbstractMotionModel(armarx::RobotStateComponentInterfacePrx robotStateProxy)
The Kinematic B\'ezier Maps.
Definition kbm.h:82
static KBM_ptr createKBM(int nDoF, int dim, const Vector &center, const Vector &spreadAngles, const Matrix &controlNet)
Factory methods.
Definition kbm.cpp:455
void ice_postUnmarshal() override
armarx::PeriodicTask< MotionModelKBM >::pointer_type updaterThreadTask
static void CreateSample(VirtualRobot::RobotNodeSetPtr nodeSet, Eigen::VectorXf jointMax, Eigen::VectorXf jointMin, VirtualRobot::RobotNodePtr root, VirtualRobot::RobotNodePtr TCP, Ice::DoubleSeq &prop, Ice::DoubleSeq &shape)
VirtualRobot::RobotPtr robot
armarx::LinkedPosePtr getPredictedPoseInternal() override
Eigen::MatrixXf getJointAngles(armarx::SharedRobotInterfacePrx robotPrx)
KBM::Models::KBM_ptr kbm
void setPoseAtLastLocalisation(const armarx::LinkedPoseBasePtr &poseAtLastLocalization, const armarx::PoseBasePtr &globalRobotPoseAtLastLocalization, const MultivariateNormalDistributionBasePtr &uncertaintyAtLastLocalization, const Ice::Current &c=Ice::emptyCurrent) override
static KBM::Models::KBM_ptr CreateKBMFromSamples(VirtualRobot::RobotPtr robot, VirtualRobot::RobotNodeSetPtr nodeSet, VirtualRobot::SceneObjectPtr referenceFrame)
MultivariateNormalDistributionBasePtr getUncertaintyInternal() override
The MultivariateNormalDistribution class.
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_DEBUG_S
The logging level for output that is only interesting while debugging.
Definition Logging.h:205
#define ARMARX_ERROR_S
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:216
#define ARMARX_INFO_S
Definition Logging.h:202
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
#define ARMARX_IMPORTANT_S
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
Definition Logging.h:210
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
#define ARMARX_WARNING_S
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:213
std::string const GlobalFrame
Variable of the global coordinate system.
Definition FramedPose.h:65
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
armarx::MatrixDouble MatrixVariant
Definition KBMData.h:36
IceInternal::Handle< LinkedPose > LinkedPosePtr
Definition LinkedPose.h:52
IceInternal::Handle< Pose > PosePtr
Definition Pose.h:306
::IceInternal::ProxyHandle<::IceProxy::armarx::SharedRobotInterface > SharedRobotInterfacePrx
Definition FramedPose.h:59
::IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface > RobotStateComponentInterfacePrx
armarx::MatrixDoublePtr MatrixVariantPtr
Definition KBMData.h:37
std::shared_ptr< KBM > KBM_ptr
Definition kbm.h:71
Eigen::MatrixXd Matrix
Definition kbm.h:40
VirtualRobot headers.
IceInternal::Handle< KBMData > KBMDataPtr
Definition KBMData.h:83