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 
29 
30 #include <MemoryX/interface/components/KBMComponentInterface.h>
31 #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
38 #include <cfloat>
39 
41 
43 
44 namespace armarx
45 {
46  /**
47  * @class KBMComponentPropertyDefinitions
48  * @brief
49  */
51  {
52  public:
54  {
55  defineOptionalProperty<std::string>(
56  "LongtermMemoryName",
57  "LongtermMemory",
58  "Name of the LongtermMemory component that should be used");
59  defineOptionalProperty<std::string>(
60  "RobotStateComponentName",
61  "RobotStateComponent",
62  "Name of the robot state component that should be used");
63  }
64  };
65 } // namespace armarx
66 
68 {
69  /**
70  * @brief calculateJointDeltas is in internal function called by solve
71  */
74  const memoryx::KBM::Vector& position,
75  const memoryx::KBM::Vector& proprioception,
76  float stepSizeFactor,
77  float maxStepSize);
78 
79  /**
80  * @brief randomFloat creates a random float between LO and HI
81  */
82  float randomFloat(float LO, float HI);
83 
84  /**
85  * @brief Creates a vector of random values between the limits
86  */
88  randomProprioception(const memoryx::KBM::Vector& lowerProprioceptionLimits,
89  const memoryx::KBM::Vector& upperProprioceptionLimits);
90 
91  /**
92  * @brief check if solution is within the limits
93  */
95  const memoryx::KBM::Vector& lowerProprioceptionLimits,
96  const memoryx::KBM::Vector& upperProprioceptionLimits);
97 
98  /**
99  * @brief apply limits to solution and return true,
100  * if solution has been changed = solution was not in limits
101  */
102  bool applyProprioceptionLimits(Eigen::Map<memoryx::KBM::Vector>& solution,
103  const memoryx::KBM::Vector& lowerProprioceptionLimits,
104  const memoryx::KBM::Vector& upperProprioceptionLimits);
105 
106  /**
107  * @brief KBMDifferentialIK::solveMany runs solve many times
108  * @param kbm
109  * @param targetPosition
110  * @param currentProprioception
111  * @param lowerProprioceptionLimits
112  * @param upperProprioceptionLimits
113  * @param solution
114  * @param maxSolves maximum number of times solve() should be called
115  * @param positionTolerance
116  * @param minimumDelta
117  * @param requireImprovment
118  * @param maxSteps
119  * @param stepSizeFactor
120  * @param maxStepSize
121  * @return
122  */
123  bool solveMany(const memoryx::KBM::Models::KBM& kbm,
124  const memoryx::KBM::Vector& targetPosition,
125  const memoryx::KBM::Vector& currentPosition,
126  const memoryx::KBM::Vector& currentProprioception,
127  const memoryx::KBM::Vector& lowerProprioceptionLimits,
128  const memoryx::KBM::Vector& upperProprioceptionLimits,
129  Eigen::Map<memoryx::KBM::Vector>& solution,
130  bool applyLimits = true,
131  int maxSolves = 25,
132  float positionTolerance = 5.0f,
133  float minimumDelta = 0.0f,
134  bool requireImprovment = false,
135  int maxSteps = 50,
136  float stepSizeFactor = 0.2f,
137  float maxStepSize = FLT_MAX);
138 
139  /**
140  * @brief solves the inverse kinematics
141  * @param kbm: the learned KBM
142  * @param targetPosition: the target position
143  * @param currentPosition: the current position
144  * @param currentProprioception: the current proprioception
145  * @param solution: will contain the joint values that solve the inverse kinematics
146  * @return true, if a good approximation has been found, false otherwise
147  */
148  bool solve(const memoryx::KBM::Models::KBM& kbm,
149  const memoryx::KBM::Vector& targetPosition,
150  const memoryx::KBM::Vector& currentPostion,
151  const memoryx::KBM::Vector& currentProprioception,
152  Eigen::Map<memoryx::KBM::Vector>& solution,
153  float positionTolerance = 5.0f,
154  float minimumDelta = 0.0f,
155  bool requireImprovment = false,
156  int maxSteps = 50,
157  float stepSizeFactor = 0.2f,
158  float maxStepSize = FLT_MAX);
159 } // namespace armarx::KBMDifferentialIK
160 
161 namespace armarx
162 {
163  /**
164  * @class KBMComponent
165  * @ingroup Memoryx-Components
166  * @brief Wrapper for the KBM class
167  */
168  class KBMComponent : virtual public armarx::Component, virtual public KBMComponentInterface
169  {
170  public:
171  /**
172  * @see armarx::ManagedIceObject::getDefaultName()
173  */
174  std::string
175  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,
220  Ice::Float threshold,
221  const Ice::Current& c = Ice::emptyCurrent) override;
222 
223  /**
224  * @brief online learning of n training samples
225  * @param name the name of the KBM
226  * @param proprioception length must be DoF * n
227  * @param position length must be Dim * n
228  * @param learnRate learning rate between 0 and 1
229  */
230  void online(const std::string& name,
231  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
232  const std::vector<memoryx::KBM::Real>& positionSequence,
233  Ice::Float learningRate,
234  const Ice::Current& c = Ice::emptyCurrent) override;
235 
236  /**
237  * @brief same as online, but evaluates after each learning iteration
238  * @param name the name of the KBM
239  * @param proprioception length must be DoF * n
240  * @param position length must be Dim * n
241  * @param learnRate learning rate between 0 and 1
242  */
243  void onlineVerbose(const std::string& name,
244  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
245  const std::vector<memoryx::KBM::Real>& positionSequence,
246  Ice::Float learningRate,
247  const std::vector<memoryx::KBM::Real>& evaluationProprioceptionSequence,
248  const std::vector<memoryx::KBM::Real>& evaluationPositionSequence,
249  const Ice::Current& c = Ice::emptyCurrent) override;
250 
251  /**
252  * @brief predict the position for n samples of proprioception (forward kinematics)
253  * @param name the name of the KBM
254  * @param proprioception length must be DoF * n
255  * @return the predicted position with length Dim * n
256  */
257  std::vector<memoryx::KBM::Real>
258  predict(const std::string& name,
259  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
260  const Ice::Current& c = Ice::emptyCurrent) override;
261 
262  /**
263  * @brief calls getErrors on the KBM and prints the result
264  * @param name the name of the KBM
265  * @param proprioception the proprioception to pass to getErrors
266  * @param position the position to pass to getErrors
267  */
268  void printErrors(const std::string& name,
269  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
270  const std::vector<memoryx::KBM::Real>& positionSequence,
271  const Ice::Current& c = Ice::emptyCurrent) override;
272 
273  /**
274  * @brief printAccumulatorStatistics prints information about the values in the accumulators
275  */
276  void printAccumulatorStatistics(int nDim,
277  int nDoF,
278  const Ice::Current& c = Ice::emptyCurrent) override;
279 
280  /**
281  * @brief accumulate adds the given position to the accumulator to use it later
282  * @param position length must be Dim * n
283  */
284  void accumulatePositions(const std::vector<memoryx::KBM::Real>& positionSequence,
285  const Ice::Current& c = Ice::emptyCurrent) override;
286 
287  /**
288  * @brief accumulates the given position in the evaluation accumulator
289  * @param position length must be Dim * n
290  */
291  void accumulateEvaluationPositions(const std::vector<memoryx::KBM::Real>& positionSequence,
292  const Ice::Current& c = Ice::emptyCurrent) override;
293 
294  /**
295  * @brief getRawJointValuesAverages calculates the average raw joint values for each joint
296  * from the data stored in the raw joint values accumulator.
297  */
298  Ice::DoubleSeq
299  getRawJointValuesAverages(int nDoF, const Ice::Current& c = Ice::emptyCurrent) override;
300 
301  /**
302  * @brief getSpreadAngles returns the spreadAngles calculated using the data in the proprioceptionAccumulator
303  */
304  Ice::DoubleSeq getSpreadAngles(int nDoF,
305  const Ice::Current& c = Ice::emptyCurrent) override;
306 
307  /**
308  * @brief accumualteProprioceptions accumulates proprioceptions
309  */
310  void accumulateProprioceptions(const std::vector<memoryx::KBM::Real>& proprioceptions,
311  const Ice::Current& c = Ice::emptyCurrent) override;
312 
313  /**
314  * @brief accumualteProprioceptions accumulates proprioceptions in the evaluate accumulator
315  */
316  void
317  accumulateEvaluationProprioceptions(const std::vector<memoryx::KBM::Real>& proprioceptions,
318  const Ice::Current& c = Ice::emptyCurrent) override;
319 
320  /**
321  * @brief accumualteRawJointValues accumulates raw joint values that will be transformed to proprioceptions later
322  */
323  void accumulateRawJointValues(const std::vector<memoryx::KBM::Real>& rawJointValuesSequence,
324  const Ice::Current& c = Ice::emptyCurrent) override;
325 
326  /**
327  * @brief setProprioceptionAccumulatorFromRawJointAccumulator updates the proprioception accumulator
328  */
330  const std::vector<memoryx::KBM::Real>& rawJointValuesAverages,
331  const Ice::Current& c = Ice::emptyCurrent) override;
332 
333  /**
334  * @brief setPositionLimits sets the position limits using the data in the position accumulator
335  */
336  void setPositionLimits(int nDim, const Ice::Current& c = Ice::emptyCurrent) override;
337 
338  /**
339  * @brief onlineAccumulator calls online after transforming the raw joint accumulator to proprioceptions
340  */
341  void onlineAccumulator(const std::string& name,
342  Ice::Float learningRate,
343  const Ice::Current& c = Ice::emptyCurrent) override;
344 
345  /**
346  * @brief onlineAccumulatorVerbose same as onlineAccumulator, but evaluates after each learning step
347  */
348  void onlineAccumulatorVerbose(const std::string& name,
349  Ice::Float learningRate,
350  const Ice::Current& c = Ice::emptyCurrent) override;
351 
352  /**
353  * @brief the same as batch but with the data from the accumulator
354  */
355  void batchAccumulator(const std::string& name,
356  Ice::Int method,
357  Ice::Float threshold,
358  const Ice::Current& c = Ice::emptyCurrent) override;
359 
360  /**
361  * @brief the same as printErrors but with the data from the accumulator
362  */
363  void printErrorsAccumulator(const std::string& name,
364  const Ice::Current& c = Ice::emptyCurrent) override;
365 
366  /**
367  * @brief the same as predict but with the data from the accumulator, however the results are currently just printed and not returned
368  */
369  void predictAccumulator(const std::string& name,
370  const Ice::Current& c = Ice::emptyCurrent) override;
371 
372  /**
373  * @brief solveGlobalIK solves the global inverse kinematics for the given position
374  * @param name the name of the KBM
375  * @param targetPosition
376  * @return the proprioception
377  */
378  std::vector<memoryx::KBM::Real>
379  solveGlobalIK(const std::string& name,
380  const std::vector<memoryx::KBM::Real>& targetPosition,
381  const Ice::Current& c = Ice::emptyCurrent) override;
382 
383  /**
384  * @brief solveDifferentialIK solves the differential inverse kinematics for the given position
385  * @param name the name of the KBM
386  * @param targetPosition
387  * @param currentPosition
388  * @param currentProprioception
389  * @return the proprioception
390  */
391  std::vector<memoryx::KBM::Real> solveDifferentialIK(
392  const std::string& name,
393  const std::vector<memoryx::KBM::Real>& targetPosition,
394  const std::vector<memoryx::KBM::Real>& currentPosition,
395  const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
396  const std::vector<memoryx::KBM::Real>& lowerProprioceptionLimitsSequence,
397  const std::vector<memoryx::KBM::Real>& upperProprioceptionLimitsSequence,
398  const Ice::Current& c = Ice::emptyCurrent) override;
399 
400  /**
401  * Returns the names of the existing KBMs
402  */
403  Ice::StringSeq kbmNames(const Ice::Current& c) override;
404 
405  /**
406  * Clears the accumulators
407  */
408  void clearAccumulators(const Ice::Current& c) override;
409 
410  void storeToMemory(const std::string&,
411  const std::string&,
412  const std::string&,
413  const std::string&,
414  const Ice::Current&) override;
415  void restoreFromMemory(const std::string&,
416  const std::string&,
417  const std::string&,
418  const std::string&,
419  const Ice::Current&) override;
420  bool isInMemory(const std::string& nodeSetName,
421  const std::string& referenceFrameName,
422  const std::string& robotName,
423  const Ice::Current& c) override;
424 
425 
426  protected:
427  /**
428  * @see armarx::ManagedIceObject::onInitComponent()
429  */
430  void onInitComponent() override;
431 
432  /**
433  * @see armarx::ManagedIceObject::onConnectComponent()
434  */
435  void onConnectComponent() override;
436 
437  /**
438  * @see armarx::ManagedIceObject::onDisconnectComponent()
439  */
440  void onDisconnectComponent() override;
441 
442  /**
443  * @see armarx::ManagedIceObject::onExitComponent()
444  */
445  void onExitComponent() override;
446 
447  /**
448  * @see PropertyUser::createPropertyDefinitions()
449  */
451 
452  /**
453  * @brief mapPosition converts the position sequence into an Eigen::Map of a Vector
454  * @param kbm the dimension of this KBM will be used
455  * @param position the position sequence
456  * @return the map
457  */
458  Eigen::Map<const memoryx::KBM::Vector>
460  const std::vector<memoryx::KBM::Real>& position);
461 
462  /**
463  * @brief mapProprioception converts the proprioception sequence into an Eigen::Map of a Vector
464  * @param kbm the DoF of this KBM will be used
465  * @param proprioception the proprioception sequence
466  * @return the map
467  */
468  Eigen::Map<const memoryx::KBM::Vector>
470  const std::vector<memoryx::KBM::Real>& proprioception);
471 
472  /**
473  * @brief mapPositions converts the position sequence into an Eigen::Map of a Matrix
474  * @param kbm the dimension of this KBM will be used
475  * @param position the position sequence
476  * @return the map
477  */
478  Eigen::Map<const memoryx::KBM::Matrix>
480  const std::vector<memoryx::KBM::Real>& position);
481 
482  /**
483  * maps a sequence to an Eigen::Map
484  */
485  Eigen::Map<const memoryx::KBM::Matrix>
486  mapMatrix(int rows, const std::vector<memoryx::KBM::Real>& data);
487 
488  /**
489  * @brief mapProprioceptions converts the proprioception sequence into an Eigen::Map of a Matrix
490  * @param kbm the DoF of this KBM will be used
491  * @param proprioception the proprioception sequence
492  * @return the map
493  */
494  Eigen::Map<const memoryx::KBM::Matrix>
496  const std::vector<memoryx::KBM::Real>& proprioception);
497 
498  /**
499  * @brief returns a pointer to the KBM with the given name if it exists or a nullptr if it doesn't
500  * @param name the name of the KBM
501  * @return pointer to the KBM or nullptr
502  */
503  memoryx::KBM::Models::KBM_ptr getKBM(const std::string& name);
504 
505  private:
506  /**
507  * @brief kbms maps KBM names to KBMs
508  */
509  std::map<std::string, memoryx::KBM::Models::KBM_ptr> kbms;
510 
511  /**
512  * @brief createdFromVirtualRobot maps KBM names to a bool indicating whether they have been created from a VirtualRobot or not
513  */
514  std::map<std::string, bool> createdFromVirtualRobot;
515 
516  /**
517  * @brief proprioceptionAccumulator is used to accumulate proprioceptions
518  */
519  std::vector<memoryx::KBM::Real> proprioceptionAccumulator;
520 
521  /**
522  * @brief positionAccumulator is used to accumulate positions
523  */
524  std::vector<memoryx::KBM::Real> positionAccumulator;
525 
526  /**
527  * @brief rawJointValuesAccumulator is used to accumulate raw joint values
528  */
529  std::vector<memoryx::KBM::Real> rawJointValuesAccumulator;
530 
531  /**
532  * @brief evaluationProprioceptionAccumulator is used to accumulate proprioceptions for evaluation
533  */
534  std::vector<memoryx::KBM::Real> evaluationProprioceptionAccumulator;
535 
536  /**
537  * @brief evaluationPositionAccumulator is used to accumulate positions for evaluation
538  */
539  std::vector<memoryx::KBM::Real> evaluationPositionAccumulator;
540 
541  memoryx::KBM::Vector minima;
542  memoryx::KBM::Vector maxima;
543 
544  memoryx::LongtermMemoryInterfacePrx longtermMemoryPrx;
545  armarx::RobotStateComponentInterfacePrx robotStateComponentPrx;
546  };
547 } // namespace armarx
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:193
armarx::KBMComponent::onExitComponent
void onExitComponent() override
Definition: KBMComponent.cpp:67
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:146
armarx::KBMComponent::storeToMemory
void storeToMemory(const std::string &, const std::string &, const std::string &, const std::string &, const Ice::Current &) override
Definition: KBMComponent.cpp:1540
armarx::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:919
memoryx::KBM::Models::KBM_ptr
std::shared_ptr< KBM > KBM_ptr
Definition: kbm.h:71
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:866
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:1402
MatrixVariant.h
armarx::KBMComponent::onInitComponent
void onInitComponent() override
Definition: KBMComponent.cpp:46
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:442
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:811
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:119
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:825
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:398
armarx::KBMComponent::clearAccumulators
void clearAccumulators(const Ice::Current &c) override
Clears the accumulators.
Definition: KBMComponent.cpp:1532
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:668
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:345
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:1143
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:685
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
armarx::KBMComponent::onDisconnectComponent
void onDisconnectComponent() override
Definition: KBMComponent.cpp:62
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:834
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:105
memoryx::KBM::Vector
Eigen::VectorXd Vector
Definition: kbm.h:41
armarx::KBMComponent::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: KBMComponent.cpp:72
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:705
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:721
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:907
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:1249
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:854
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:748
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:894
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:353
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:640
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:1614
armarx::KBMComponent
Wrapper for the KBM class.
Definition: KBMComponent.h:168
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:879
armarx::KBMComponent::restoreFromMemory
void restoreFromMemory(const std::string &, const std::string &, const std::string &, const std::string &, const Ice::Current &) override
Definition: KBMComponent.cpp:1571
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:1096
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:96
armarx::KBMComponentPropertyDefinitions
Definition: KBMComponent.h:50
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:922
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:793
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:168
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:1165
armarx::KBMComponent::onConnectComponent
void onConnectComponent() override
Definition: KBMComponent.cpp:53
armarx::Component
Baseclass for all ArmarX ManagedIceObjects requiring properties.
Definition: Component.h:91
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:87
armarx::KBMComponent::getDefaultName
std::string getDefaultName() const override
Definition: KBMComponent.h:175
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:69
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:803
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:1519
memoryx::KBM::Models::KBM
The Kinematic B\'ezier Maps.
Definition: kbm.h:81
armarx::VariantType::Int
const VariantTypeId Int
Definition: Variant.h:917
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:840
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:968
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:133
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:1203
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:1102
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
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:604
armarx::KBMDifferentialIK
Definition: KBMComponent.h:67