KBMComponent.h
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 #pragma once
26 
28 
29 #include <MemoryX/interface/components/KBMComponentInterface.h>
30 #include <MemoryX/interface/components/LongtermMemoryInterface.h>
32 
33 /*
34  * using these #define's here isn't nice, but it works
35  */
36 //#define KBM_NO_ARMAR_X
37 //#define KBM_USE_SINGLE_PRECISION
40 
41 #include <cfloat>
42 
43 namespace armarx
44 {
45  /**
46  * @class KBMComponentPropertyDefinitions
47  * @brief
48  */
51  {
52  public:
55  {
56  defineOptionalProperty<std::string>("LongtermMemoryName", "LongtermMemory", "Name of the LongtermMemory component that should be used");
57  defineOptionalProperty<std::string>("RobotStateComponentName", "RobotStateComponent", "Name of the robot state component that should be used");
58  }
59  };
60 }
61 
63 {
64  /**
65  * @brief calculateJointDeltas is in internal function called by solve
66  */
69  const memoryx::KBM::Vector& position,
70  const memoryx::KBM::Vector& proprioception,
71  float stepSizeFactor,
72  float maxStepSize);
73 
74  /**
75  * @brief randomFloat creates a random float between LO and HI
76  */
77  float randomFloat(float LO, float HI);
78 
79  /**
80  * @brief Creates a vector of random values between the limits
81  */
83  const memoryx::KBM::Vector& lowerProprioceptionLimits,
84  const memoryx::KBM::Vector& upperProprioceptionLimits);
85 
86  /**
87  * @brief check if solution is within the limits
88  */
90  const memoryx::KBM::Vector& solution,
91  const memoryx::KBM::Vector& lowerProprioceptionLimits,
92  const memoryx::KBM::Vector& upperProprioceptionLimits);
93 
94  /**
95  * @brief apply limits to solution and return true,
96  * if solution has been changed = solution was not in limits
97  */
99  Eigen::Map<memoryx::KBM::Vector>& solution,
100  const memoryx::KBM::Vector& lowerProprioceptionLimits,
101  const memoryx::KBM::Vector& upperProprioceptionLimits);
102 
103  /**
104  * @brief KBMDifferentialIK::solveMany runs solve many times
105  * @param kbm
106  * @param targetPosition
107  * @param currentProprioception
108  * @param lowerProprioceptionLimits
109  * @param upperProprioceptionLimits
110  * @param solution
111  * @param maxSolves maximum number of times solve() should be called
112  * @param positionTolerance
113  * @param minimumDelta
114  * @param requireImprovment
115  * @param maxSteps
116  * @param stepSizeFactor
117  * @param maxStepSize
118  * @return
119  */
120  bool solveMany(
121  const memoryx::KBM::Models::KBM& kbm,
122  const memoryx::KBM::Vector& targetPosition,
123  const memoryx::KBM::Vector& currentPosition,
124  const memoryx::KBM::Vector& currentProprioception,
125  const memoryx::KBM::Vector& lowerProprioceptionLimits,
126  const memoryx::KBM::Vector& upperProprioceptionLimits,
127  Eigen::Map<memoryx::KBM::Vector>& solution,
128  bool applyLimits = true,
129  int maxSolves = 25,
130  float positionTolerance = 5.0f,
131  float minimumDelta = 0.0f,
132  bool requireImprovment = false,
133  int maxSteps = 50,
134  float stepSizeFactor = 0.2f,
135  float maxStepSize = FLT_MAX);
136 
137  /**
138  * @brief solves the inverse kinematics
139  * @param kbm: the learned KBM
140  * @param targetPosition: the target position
141  * @param currentPosition: the current position
142  * @param currentProprioception: the current proprioception
143  * @param solution: will contain the joint values that solve the inverse kinematics
144  * @return true, if a good approximation has been found, false otherwise
145  */
146  bool solve(const memoryx::KBM::Models::KBM& kbm,
147  const memoryx::KBM::Vector& targetPosition,
148  const memoryx::KBM::Vector& currentPostion,
149  const memoryx::KBM::Vector& currentProprioception,
150  Eigen::Map<memoryx::KBM::Vector>& solution,
151  float positionTolerance = 5.0f,
152  float minimumDelta = 0.0f,
153  bool requireImprovment = false,
154  int maxSteps = 50,
155  float stepSizeFactor = 0.2f,
156  float maxStepSize = FLT_MAX
157  );
158 }
159 
160 namespace armarx
161 {
162  /**
163  * @class KBMComponent
164  * @ingroup Memoryx-Components
165  * @brief Wrapper for the KBM class
166  */
167  class KBMComponent :
168  virtual public armarx::Component,
169  virtual public KBMComponentInterface
170  {
171  public:
172  /**
173  * @see armarx::ManagedIceObject::getDefaultName()
174  */
175  std::string getDefaultName() const override
176  {
177  return "KBMComponent";
178  }
179 
180  /**
181  * @brief createKBM creates a new KBM and makes it available under the given name
182  * @param name the name of the KBM
183  * @param nDoF degrees of freedom
184  * @param dim dimensions
185  * @param spreadAngle the common spreadAngle for joints
186  */
187  void createKBM(const std::string& name,
188  Ice::Int nDoF,
189  Ice::Int dim,
190  Ice::Float spreadAngle,
191  const Ice::Current& c = Ice::emptyCurrent) override;
192 
193  /**
194  * @brief createArmar3KBM creates a KBM from a VirtualRobot model
195  * @param name the KBM will be available under this name
196  * @param activeJoints the names of the joints that are used
197  * @param tcpName name of the joint that corresponds best to the tool center point
198  * @param useOrientation use only the position (3 dimensions) or position and orientation (9 dimensions in total)
199  */
200  void createArmar3KBM(const std::string& name,
201  const Ice::StringSeq& robotNodeNames,
202  const std::vector<memoryx::KBM::Real>& jointValueAverages,
203  const std::vector<memoryx::KBM::Real>& spreadAnglesSequence,
204  const std::string& tcpName,
205  bool useOrientation,
206  const Ice::Current& c = Ice::emptyCurrent) override;
207 
208  /**
209  * @brief batch learning of n training samples
210  * @param name the name of the KBM
211  * @param proprioception length must be DoF * n
212  * @param position length must be Dim * n
213  * @param method will be mapped to the Enum in the KBM class, currently 0 = STANDARD, 1 = PLS
214  * @param threshold should equal the expected mean positioning error
215  */
216  void batch(const std::string& name,
217  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
218  const std::vector<memoryx::KBM::Real>& positionSequence,
219  Ice::Int method, Ice::Float threshold,
220  const Ice::Current& c = Ice::emptyCurrent) override;
221 
222  /**
223  * @brief online learning of n training samples
224  * @param name the name of the KBM
225  * @param proprioception length must be DoF * n
226  * @param position length must be Dim * n
227  * @param learnRate learning rate between 0 and 1
228  */
229  void online(const std::string& name,
230  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
231  const std::vector<memoryx::KBM::Real>& positionSequence,
232  Ice::Float learningRate,
233  const Ice::Current& c = Ice::emptyCurrent) override;
234 
235  /**
236  * @brief same as online, but evaluates after each learning iteration
237  * @param name the name of the KBM
238  * @param proprioception length must be DoF * n
239  * @param position length must be Dim * n
240  * @param learnRate learning rate between 0 and 1
241  */
242  void onlineVerbose(const std::string& name,
243  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
244  const std::vector<memoryx::KBM::Real>& positionSequence,
245  Ice::Float learningRate,
246  const std::vector<memoryx::KBM::Real>& evaluationProprioceptionSequence,
247  const std::vector<memoryx::KBM::Real>& evaluationPositionSequence,
248  const Ice::Current& c = Ice::emptyCurrent) override;
249 
250  /**
251  * @brief predict the position for n samples of proprioception (forward kinematics)
252  * @param name the name of the KBM
253  * @param proprioception length must be DoF * n
254  * @return the predicted position with length Dim * n
255  */
256  std::vector<memoryx::KBM::Real> predict(const std::string& name,
257  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
258  const Ice::Current& c = Ice::emptyCurrent) override;
259 
260  /**
261  * @brief calls getErrors on the KBM and prints the result
262  * @param name the name of the KBM
263  * @param proprioception the proprioception to pass to getErrors
264  * @param position the position to pass to getErrors
265  */
266  void printErrors(const std::string& name,
267  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
268  const std::vector<memoryx::KBM::Real>& positionSequence,
269  const Ice::Current& c = Ice::emptyCurrent) override;
270 
271  /**
272  * @brief printAccumulatorStatistics prints information about the values in the accumulators
273  */
274  void printAccumulatorStatistics(int nDim,
275  int nDoF,
276  const Ice::Current& c = Ice::emptyCurrent) override;
277 
278  /**
279  * @brief accumulate adds the given position to the accumulator to use it later
280  * @param position length must be Dim * n
281  */
282  void accumulatePositions(const std::vector<memoryx::KBM::Real>& positionSequence,
283  const Ice::Current& c = Ice::emptyCurrent) override;
284 
285  /**
286  * @brief accumulates the given position in the evaluation accumulator
287  * @param position length must be Dim * n
288  */
289  void accumulateEvaluationPositions(const std::vector<memoryx::KBM::Real>& positionSequence,
290  const Ice::Current& c = Ice::emptyCurrent) override;
291 
292  /**
293  * @brief getRawJointValuesAverages calculates the average raw joint values for each joint
294  * from the data stored in the raw joint values accumulator.
295  */
296  Ice::DoubleSeq getRawJointValuesAverages(int nDoF, const Ice::Current& c = Ice::emptyCurrent) override;
297 
298  /**
299  * @brief getSpreadAngles returns the spreadAngles calculated using the data in the proprioceptionAccumulator
300  */
301  Ice::DoubleSeq getSpreadAngles(int nDoF, const Ice::Current& c = Ice::emptyCurrent) override;
302 
303  /**
304  * @brief accumualteProprioceptions accumulates proprioceptions
305  */
306  void accumulateProprioceptions(const std::vector<memoryx::KBM::Real>& proprioceptions,
307  const Ice::Current& c = Ice::emptyCurrent) override;
308 
309  /**
310  * @brief accumualteProprioceptions accumulates proprioceptions in the evaluate accumulator
311  */
312  void accumulateEvaluationProprioceptions(const std::vector<memoryx::KBM::Real>& proprioceptions,
313  const Ice::Current& c = Ice::emptyCurrent) override;
314 
315  /**
316  * @brief accumualteRawJointValues accumulates raw joint values that will be transformed to proprioceptions later
317  */
318  void accumulateRawJointValues(const std::vector<memoryx::KBM::Real>& rawJointValuesSequence,
319  const Ice::Current& c = Ice::emptyCurrent) override;
320 
321  /**
322  * @brief setProprioceptionAccumulatorFromRawJointAccumulator updates the proprioception accumulator
323  */
324  void setProprioceptionAccumulatorFromRawJointAccumulator(const std::vector<memoryx::KBM::Real>& rawJointValuesAverages,
325  const Ice::Current& c = Ice::emptyCurrent) override;
326 
327  /**
328  * @brief setPositionLimits sets the position limits using the data in the position accumulator
329  */
330  void setPositionLimits(int nDim, const Ice::Current& c = Ice::emptyCurrent) override;
331 
332  /**
333  * @brief onlineAccumulator calls online after transforming the raw joint accumulator to proprioceptions
334  */
335  void onlineAccumulator(const std::string& name,
336  Ice::Float learningRate,
337  const Ice::Current& c = Ice::emptyCurrent) override;
338 
339  /**
340  * @brief onlineAccumulatorVerbose same as onlineAccumulator, but evaluates after each learning step
341  */
342  void onlineAccumulatorVerbose(const std::string& name,
343  Ice::Float learningRate,
344  const Ice::Current& c = Ice::emptyCurrent) override;
345 
346  /**
347  * @brief the same as batch but with the data from the accumulator
348  */
349  void batchAccumulator(const std::string& name,
350  Ice::Int method, Ice::Float threshold,
351  const Ice::Current& c = Ice::emptyCurrent) override;
352 
353  /**
354  * @brief the same as printErrors but with the data from the accumulator
355  */
356  void printErrorsAccumulator(const std::string& name,
357  const Ice::Current& c = Ice::emptyCurrent) override;
358 
359  /**
360  * @brief the same as predict but with the data from the accumulator, however the results are currently just printed and not returned
361  */
362  void predictAccumulator(const std::string& name,
363  const Ice::Current& c = Ice::emptyCurrent) override;
364 
365  /**
366  * @brief solveGlobalIK solves the global inverse kinematics for the given position
367  * @param name the name of the KBM
368  * @param targetPosition
369  * @return the proprioception
370  */
371  std::vector<memoryx::KBM::Real> solveGlobalIK(const std::string& name,
372  const std::vector<memoryx::KBM::Real>& targetPosition,
373  const Ice::Current& c = Ice::emptyCurrent) override;
374 
375  /**
376  * @brief solveDifferentialIK solves the differential inverse kinematics for the given position
377  * @param name the name of the KBM
378  * @param targetPosition
379  * @param currentPosition
380  * @param currentProprioception
381  * @return the proprioception
382  */
383  std::vector<memoryx::KBM::Real> solveDifferentialIK(const std::string& name,
384  const std::vector<memoryx::KBM::Real>& targetPosition,
385  const std::vector<memoryx::KBM::Real>& currentPosition,
386  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
387  const std::vector<memoryx::KBM::Real>& lowerProprioceptionLimitsSequence,
388  const std::vector<memoryx::KBM::Real>& upperProprioceptionLimitsSequence,
389  const Ice::Current& c = Ice::emptyCurrent) override;
390 
391  /**
392  * Returns the names of the existing KBMs
393  */
394  Ice::StringSeq kbmNames(const Ice::Current& c) override;
395 
396  /**
397  * Clears the accumulators
398  */
399  void clearAccumulators(const Ice::Current& c) override;
400 
401  void storeToMemory(const std::string&, const std::string&, const std::string&, const std::string&, const Ice::Current&) override;
402  void restoreFromMemory(const std::string&, const std::string&, const std::string&, const std::string&, const Ice::Current&) override;
403  bool isInMemory(const std::string& nodeSetName, const std::string& referenceFrameName, const std::string& robotName, const Ice::Current& c) override;
404 
405 
406  protected:
407  /**
408  * @see armarx::ManagedIceObject::onInitComponent()
409  */
410  void onInitComponent() override;
411 
412  /**
413  * @see armarx::ManagedIceObject::onConnectComponent()
414  */
415  void onConnectComponent() override;
416 
417  /**
418  * @see armarx::ManagedIceObject::onDisconnectComponent()
419  */
420  void onDisconnectComponent() override;
421 
422  /**
423  * @see armarx::ManagedIceObject::onExitComponent()
424  */
425  void onExitComponent() override;
426 
427  /**
428  * @see PropertyUser::createPropertyDefinitions()
429  */
431 
432  /**
433  * @brief mapPosition converts the position sequence into an Eigen::Map of a Vector
434  * @param kbm the dimension of this KBM will be used
435  * @param position the position sequence
436  * @return the map
437  */
438  Eigen::Map<const memoryx::KBM::Vector> mapPosition(const memoryx::KBM::Models::KBM& kbm,
439  const std::vector<memoryx::KBM::Real>& position);
440 
441  /**
442  * @brief mapProprioception converts the proprioception sequence into an Eigen::Map of a Vector
443  * @param kbm the DoF of this KBM will be used
444  * @param proprioception the proprioception sequence
445  * @return the map
446  */
447  Eigen::Map<const memoryx::KBM::Vector> mapProprioception(const memoryx::KBM::Models::KBM& kbm,
448  const std::vector<memoryx::KBM::Real>& proprioception);
449 
450  /**
451  * @brief mapPositions converts the position sequence into an Eigen::Map of a Matrix
452  * @param kbm the dimension of this KBM will be used
453  * @param position the position sequence
454  * @return the map
455  */
456  Eigen::Map<const memoryx::KBM::Matrix> mapPositions(const memoryx::KBM::Models::KBM& kbm,
457  const std::vector<memoryx::KBM::Real>& position);
458 
459  /**
460  * maps a sequence to an Eigen::Map
461  */
462  Eigen::Map<const memoryx::KBM::Matrix> mapMatrix(int rows,
463  const std::vector<memoryx::KBM::Real>& data);
464 
465  /**
466  * @brief mapProprioceptions converts the proprioception sequence into an Eigen::Map of a Matrix
467  * @param kbm the DoF of this KBM will be used
468  * @param proprioception the proprioception sequence
469  * @return the map
470  */
471  Eigen::Map<const memoryx::KBM::Matrix> mapProprioceptions(const memoryx::KBM::Models::KBM& kbm,
472  const std::vector<memoryx::KBM::Real>& proprioception);
473 
474  /**
475  * @brief returns a pointer to the KBM with the given name if it exists or a nullptr if it doesn't
476  * @param name the name of the KBM
477  * @return pointer to the KBM or nullptr
478  */
479  memoryx::KBM::Models::KBM_ptr getKBM(const std::string& name);
480 
481  private:
482  /**
483  * @brief kbms maps KBM names to KBMs
484  */
485  std::map<std::string, memoryx::KBM::Models::KBM_ptr> kbms;
486 
487  /**
488  * @brief createdFromVirtualRobot maps KBM names to a bool indicating whether they have been created from a VirtualRobot or not
489  */
490  std::map<std::string, bool> createdFromVirtualRobot;
491 
492  /**
493  * @brief proprioceptionAccumulator is used to accumulate proprioceptions
494  */
495  std::vector<memoryx::KBM::Real> proprioceptionAccumulator;
496 
497  /**
498  * @brief positionAccumulator is used to accumulate positions
499  */
500  std::vector<memoryx::KBM::Real> positionAccumulator;
501 
502  /**
503  * @brief rawJointValuesAccumulator is used to accumulate raw joint values
504  */
505  std::vector<memoryx::KBM::Real> rawJointValuesAccumulator;
506 
507  /**
508  * @brief evaluationProprioceptionAccumulator is used to accumulate proprioceptions for evaluation
509  */
510  std::vector<memoryx::KBM::Real> evaluationProprioceptionAccumulator;
511 
512  /**
513  * @brief evaluationPositionAccumulator is used to accumulate positions for evaluation
514  */
515  std::vector<memoryx::KBM::Real> evaluationPositionAccumulator;
516 
517  memoryx::KBM::Vector minima;
518  memoryx::KBM::Vector maxima;
519 
520  memoryx::LongtermMemoryInterfacePrx longtermMemoryPrx;
521  armarx::RobotStateComponentInterfacePrx robotStateComponentPrx;
522  };
523 }
kbm.h
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
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::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::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:918
memoryx::KBM::Models::KBM_ptr
std::shared_ptr< KBM > KBM_ptr
Definition: kbm.h:68
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
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
MatrixVariant.h
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
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
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:333
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
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
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
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
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
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::KBMComponentPropertyDefinitions::KBMComponentPropertyDefinitions
KBMComponentPropertyDefinitions(std::string prefix)
Definition: KBMComponent.h:53
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
armarx::KBMComponent
Wrapper for the KBM class.
Definition: KBMComponent.h:167
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
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
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
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::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
Component.h
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
armarx::Component
Baseclass for all ArmarX ManagedIceObjects requiring properties.
Definition: Component.h:95
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
armarx::KBMComponent::getDefaultName
std::string getDefaultName() const override
Definition: KBMComponent.h:175
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:70
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
IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface >
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::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
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
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
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
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
armarx::KBMDifferentialIK
Definition: KBMComponent.h:62