Go to the documentation of this file.
30 #include <MemoryX/interface/components/KBMComponentInterface.h>
31 #include <MemoryX/interface/components/LongtermMemoryInterface.h>
55 defineOptionalProperty<std::string>(
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");
129 Eigen::Map<memoryx::KBM::Vector>& solution,
130 bool applyLimits =
true,
132 float positionTolerance = 5.0f,
133 float minimumDelta = 0.0f,
134 bool requireImprovment =
false,
136 float stepSizeFactor = 0.2f,
137 float maxStepSize = FLT_MAX);
152 Eigen::Map<memoryx::KBM::Vector>& solution,
153 float positionTolerance = 5.0f,
154 float minimumDelta = 0.0f,
155 bool requireImprovment =
false,
157 float stepSizeFactor = 0.2f,
158 float maxStepSize = FLT_MAX);
177 return "KBMComponent";
191 const Ice::Current&
c = Ice::emptyCurrent)
override;
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,
206 const Ice::Current&
c = Ice::emptyCurrent)
override;
216 void batch(
const std::string& name,
217 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
218 const std::vector<memoryx::KBM::Real>& positionSequence,
221 const Ice::Current&
c = Ice::emptyCurrent)
override;
230 void online(
const std::string& name,
231 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
232 const std::vector<memoryx::KBM::Real>& positionSequence,
234 const Ice::Current&
c = Ice::emptyCurrent)
override;
244 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
245 const std::vector<memoryx::KBM::Real>& positionSequence,
247 const std::vector<memoryx::KBM::Real>& evaluationProprioceptionSequence,
248 const std::vector<memoryx::KBM::Real>& evaluationPositionSequence,
249 const Ice::Current&
c = Ice::emptyCurrent)
override;
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;
269 const std::vector<memoryx::KBM::Real>& proprioceptionSequence,
270 const std::vector<memoryx::KBM::Real>& positionSequence,
271 const Ice::Current&
c = Ice::emptyCurrent)
override;
278 const Ice::Current&
c = Ice::emptyCurrent)
override;
285 const Ice::Current&
c = Ice::emptyCurrent)
override;
292 const Ice::Current&
c = Ice::emptyCurrent)
override;
305 const Ice::Current&
c = Ice::emptyCurrent)
override;
311 const Ice::Current&
c = Ice::emptyCurrent)
override;
318 const Ice::Current&
c = Ice::emptyCurrent)
override;
324 const Ice::Current&
c = Ice::emptyCurrent)
override;
330 const std::vector<memoryx::KBM::Real>& rawJointValuesAverages,
331 const Ice::Current&
c = Ice::emptyCurrent)
override;
343 const Ice::Current&
c = Ice::emptyCurrent)
override;
350 const Ice::Current&
c = Ice::emptyCurrent)
override;
358 const Ice::Current&
c = Ice::emptyCurrent)
override;
364 const Ice::Current&
c = Ice::emptyCurrent)
override;
370 const Ice::Current&
c = Ice::emptyCurrent)
override;
378 std::vector<memoryx::KBM::Real>
380 const std::vector<memoryx::KBM::Real>& targetPosition,
381 const Ice::Current&
c = Ice::emptyCurrent)
override;
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;
403 Ice::StringSeq
kbmNames(
const Ice::Current&
c)
override;
414 const Ice::Current&)
override;
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;
458 Eigen::Map<const memoryx::KBM::Vector>
460 const std::vector<memoryx::KBM::Real>& position);
468 Eigen::Map<const memoryx::KBM::Vector>
470 const std::vector<memoryx::KBM::Real>& proprioception);
478 Eigen::Map<const memoryx::KBM::Matrix>
480 const std::vector<memoryx::KBM::Real>& position);
485 Eigen::Map<const memoryx::KBM::Matrix>
486 mapMatrix(
int rows,
const std::vector<memoryx::KBM::Real>&
data);
494 Eigen::Map<const memoryx::KBM::Matrix>
496 const std::vector<memoryx::KBM::Real>& proprioception);
509 std::map<std::string, memoryx::KBM::Models::KBM_ptr> kbms;
514 std::map<std::string, bool> createdFromVirtualRobot;
519 std::vector<memoryx::KBM::Real> proprioceptionAccumulator;
524 std::vector<memoryx::KBM::Real> positionAccumulator;
529 std::vector<memoryx::KBM::Real> rawJointValuesAccumulator;
534 std::vector<memoryx::KBM::Real> evaluationProprioceptionAccumulator;
539 std::vector<memoryx::KBM::Real> evaluationPositionAccumulator;
544 memoryx::LongtermMemoryInterfacePrx longtermMemoryPrx;
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
void onExitComponent() override
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
void storeToMemory(const std::string &, const std::string &, const std::string &, const std::string &, const Ice::Current &) override
const VariantTypeId Float
std::shared_ptr< KBM > KBM_ptr
void accumulateProprioceptions(const std::vector< memoryx::KBM::Real > &proprioceptions, const Ice::Current &c=Ice::emptyCurrent) override
accumualteProprioceptions accumulates proprioceptions
bool solve(const memoryx::KBM::Models::KBM &kbm, const memoryx::KBM::Vector &targetPosition, const memoryx::KBM::Vector ¤tPostion, const memoryx::KBM::Vector ¤tProprioception, 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
void onInitComponent() override
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
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
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
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
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
void clearAccumulators(const Ice::Current &c) override
Clears the accumulators.
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
memoryx::KBM::Vector randomProprioception(const memoryx::KBM::Vector &lowerProprioceptionLimits, const memoryx::KBM::Vector &upperProprioceptionLimits)
Creates a vector of random values between the limits.
void printAccumulatorStatistics(int nDim, int nDoF, const Ice::Current &c=Ice::emptyCurrent) override
printAccumulatorStatistics prints information about the values in the accumulators
void onDisconnectComponent() override
void printErrorsAccumulator(const std::string &name, const Ice::Current &c=Ice::emptyCurrent) override
the same as printErrors but with the data from the accumulator
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
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
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...
Ice::DoubleSeq getSpreadAngles(int nDoF, const Ice::Current &c=Ice::emptyCurrent) override
getSpreadAngles returns the spreadAngles calculated using the data in the proprioceptionAccumulator
void accumulateEvaluationProprioceptions(const std::vector< memoryx::KBM::Real > &proprioceptions, const Ice::Current &c=Ice::emptyCurrent) override
accumualteProprioceptions accumulates proprioceptions in the evaluate accumulator
bool solveMany(const memoryx::KBM::Models::KBM &kbm, const memoryx::KBM::Vector &targetPosition, const memoryx::KBM::Vector ¤tPosition, const memoryx::KBM::Vector ¤tProprioception, 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.
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
void setProprioceptionAccumulatorFromRawJointAccumulator(const std::vector< memoryx::KBM::Real > &rawJointValuesAverages, const Ice::Current &c=Ice::emptyCurrent) override
setProprioceptionAccumulatorFromRawJointAccumulator updates the proprioception accumulator
void accumulateEvaluationPositions(const std::vector< memoryx::KBM::Real > &positionSequence, const Ice::Current &c=Ice::emptyCurrent) override
accumulates the given position in the evaluation accumulator
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
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
KBMComponentPropertyDefinitions(std::string prefix)
bool isInMemory(const std::string &nodeSetName, const std::string &referenceFrameName, const std::string &robotName, const Ice::Current &c) override
Wrapper for the KBM class.
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...
void restoreFromMemory(const std::string &, const std::string &, const std::string &, const std::string &, const Ice::Current &) override
float randomFloat(float LO, float HI)
randomFloat creates a random float between LO and HI
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
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
void setPositionLimits(int nDim, const Ice::Current &c=Ice::emptyCurrent) override
setPositionLimits sets the position limits using the data in the position accumulator
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
bool checkProprioceptionLimits(const memoryx::KBM::Vector &solution, const memoryx::KBM::Vector &lowerProprioceptionLimits, const memoryx::KBM::Vector &upperProprioceptionLimits)
check if solution is within the limits
void onConnectComponent() override
Baseclass for all ArmarX ManagedIceObjects requiring properties.
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
std::string getDefaultName() const override
Default component property definition container.
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
Ice::StringSeq kbmNames(const Ice::Current &c) override
Returns the names of the existing KBMs.
The Kinematic B\'ezier Maps.
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...
std::vector< memoryx::KBM::Real > solveDifferentialIK(const std::string &name, const std::vector< memoryx::KBM::Real > &targetPosition, const std::vector< memoryx::KBM::Real > ¤tPosition, 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
Eigen::Map< const memoryx::KBM::Matrix > mapMatrix(int rows, const std::vector< memoryx::KBM::Real > &data)
maps a sequence to an Eigen::Map
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
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
This file offers overloads of toIce() and fromIce() functions for STL container types.
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)