Home Previous Up Next Index

armarx::KBMComponentInterface

Overview

interface KBMComponentInterface

Operation Index

createKBM
@brief createKBM creates a new KBM and makes it available under the given name @param name the name of the KBM @param nDoF degrees of freedom @param dim dimensions @param spreadAngle the common spreadAngle for joints
createArmar3KBM
@brief createArmar3KBM creates a KBM from a VirtualRobot model @param name the KBM will be available under this name @param activeJoints the names of the joints that are used @param tcpName name of the joint that corresponds best to the tool center point @param useOrientation use only the position (3 dimensions) or position and orientation (9 dimensions in total)
batch
@brief batch learning of n training samples @param name the name of the KBM @param proprioception length must be DoF * n @param position length must be Dim * n @param method will be mapped to the Enum in the KBM class, currently 0 = STANDARD, 1 = PLS @param threshold should equal the expected mean positioning error
online
@brief online learning of n training samples @param name the name of the KBM @param proprioception length must be DoF * n @param position length must be Dim * n @param learnRate learning rate between 0 and 1
onlineVerbose
@brief online learning of n training samples @param name the name of the KBM @param proprioception length must be DoF * n @param position length must be Dim * n @param learnRate learning rate between 0 and 1
predict
@brief predict the position for n samples of proprioception (forward kinematics) @param name the name of the KBM @param proprioception length must be DoF * n @return the predicted position with length Dim * n
printErrors
@brief calls getErrors on the KBM and prints the result @param name the name of the KBM @param proprioception the proprioception to pass to getErrors @param position the position to pass to getErrors
accumulatePositions
@brief accumulate adds the given position to the accumulator to use it later @param position length must be Dim * n
accumulateEvaluationPositions
getRawJointValuesAverages
@brief getRawJointValuesAverages calculates the average raw joint values for each joint from the data stored in the raw joint values accumulator.
getSpreadAngles
@brief getSpreadAngles returns the spreadAngles calculated using the data in the proprioceptionAccumulator
accumulateProprioceptions
@brief accumualteProprioceptions accumulates proprioceptions
accumulateEvaluationProprioceptions
accumulateRawJointValues
@brief accumualteRawJointValues accumulates raw joint values that will be transformed to proprioceptions later
setProprioceptionAccumulatorFromRawJointAccumulator
@brief setProprioceptionAccumulatorFromRawJointAccumulator updates the proprioception accumulator
setPositionLimits
@brief setPositionLimits sets the position limits using the data in the position accumulator
onlineAccumulator
@brief onlineAccumulator calls online after transforming the raw joint accumulator to proprioceptions
onlineAccumulatorVerbose
@brief onlineAccumulatorVerbose same as onlineAccumulator, but evaluates after each learning step
batchAccumulator
@brief the same as batch but with the data from the accumulator
printErrorsAccumulator
@brief the same as printErrors but with the data from the accumulator
printAccumulatorStatistics
@brief printAccumulatorStatistics prints information about the values in the accumulators
predictAccumulator
@brief the same as predict but with the data from the accumulator, however the results are currently just printed and not returned
solveGlobalIK
@brief solveGlobalIK solves the global inverse kinematics for the given position @param name the name of the KBM @param targetPosition @return the proprioception
solveDifferentialIK
@brief solveDifferentialIK solves the differential inverse kinematics for the given position @param name the name of the KBM @param targetPosition @param currentPosition @param currentProprioception @return the proprioception
storeToMemory
restoreFromMemory
isInMemory
kbmNames
Returns the names of the existing KBMs
clearAccumulators
Clears the accumulators

Operations

void createKBM(string name, int nDoF, int dim, float spreadAngle)

@brief createKBM creates a new KBM and makes it available under the given name

Parameters

name
the name of the KBM
nDoF
degrees of freedom
dim
dimensions
spreadAngle
the common spreadAngle for joints

void createArmar3KBM(string name, ::Ice::StringSeq activeJoints, ::Ice::DoubleSeq jointValueAverages, ::Ice::DoubleSeq spreadAngles, string tcpName, bool useOrientation)

@brief createArmar3KBM creates a KBM from a VirtualRobot model

Parameters

name
the KBM will be available under this name
activeJoints
the names of the joints that are used
tcpName
name of the joint that corresponds best to the tool center point
useOrientation
use only the position (3 dimensions) or position and orientation (9 dimensions in total)

void batch(string name, ::Ice::DoubleSeq proprioception, ::Ice::DoubleSeq position, int method, float threshold)

@brief batch learning of n training samples

Parameters

name
the name of the KBM
proprioception
length must be DoF * n
position
length must be Dim * n
method
will be mapped to the Enum in the KBM class, currently 0 = STANDARD, 1 = PLS
threshold
should equal the expected mean positioning error

void online(string name, ::Ice::DoubleSeq proprioception, ::Ice::DoubleSeq position, float learnRate)

@brief online learning of n training samples

Parameters

name
the name of the KBM
proprioception
length must be DoF * n
position
length must be Dim * n
learnRate
learning rate between 0 and 1

void onlineVerbose(string name, ::Ice::DoubleSeq proprioception, ::Ice::DoubleSeq position, float learnRate, ::Ice::DoubleSeq evaluationProprioception, ::Ice::DoubleSeq evaluationPosition)

@brief online learning of n training samples

Parameters

name
the name of the KBM
proprioception
length must be DoF * n
position
length must be Dim * n
learnRate
learning rate between 0 and 1

::Ice::DoubleSeq predict(string name, ::Ice::DoubleSeq proprioception)

@brief predict the position for n samples of proprioception (forward kinematics)

Parameters

name
the name of the KBM
proprioception
length must be DoF * n

Return Value

the predicted position with length Dim * n

void printErrors(string name, ::Ice::DoubleSeq proprioception, ::Ice::DoubleSeq position)

@brief calls getErrors on the KBM and prints the result

Parameters

name
the name of the KBM
proprioception
the proprioception to pass to getErrors
position
the position to pass to getErrors

void accumulatePositions(::Ice::DoubleSeq position)

@brief accumulate adds the given position to the accumulator to use it later

Parameters

position
length must be Dim * n

void accumulateEvaluationPositions(::Ice::DoubleSeq position)

::Ice::DoubleSeq getRawJointValuesAverages(int nDoF)

@brief getRawJointValuesAverages calculates the average raw joint values for each joint from the data stored in the raw joint values accumulator.

::Ice::DoubleSeq getSpreadAngles(int nDoF)

@brief getSpreadAngles returns the spreadAngles calculated using the data in the proprioceptionAccumulator

void accumulateProprioceptions(::Ice::DoubleSeq proprioceptions)

@brief accumualteProprioceptions accumulates proprioceptions

void accumulateEvaluationProprioceptions(::Ice::DoubleSeq proprioceptions)

void accumulateRawJointValues(::Ice::DoubleSeq rawJointValuesSequence)

@brief accumualteRawJointValues accumulates raw joint values that will be transformed to proprioceptions later

void setProprioceptionAccumulatorFromRawJointAccumulator(::Ice::DoubleSeq rawJointValuesAverages)

@brief setProprioceptionAccumulatorFromRawJointAccumulator updates the proprioception accumulator

void setPositionLimits(int nDim)

@brief setPositionLimits sets the position limits using the data in the position accumulator

void onlineAccumulator(string name, float learningRate)

@brief onlineAccumulator calls online after transforming the raw joint accumulator to proprioceptions

void onlineAccumulatorVerbose(string name, float learningRate)

@brief onlineAccumulatorVerbose same as onlineAccumulator, but evaluates after each learning step

void batchAccumulator(string name, int method, float threshold)

@brief the same as batch but with the data from the accumulator

void printErrorsAccumulator(string name)

@brief the same as printErrors but with the data from the accumulator

void printAccumulatorStatistics(int nDim, int nDoF)

@brief printAccumulatorStatistics prints information about the values in the accumulators

void predictAccumulator(string name)

@brief the same as predict but with the data from the accumulator, however the results are currently just printed and not returned

::Ice::DoubleSeq solveGlobalIK(string name, ::Ice::DoubleSeq targetPosition)

@brief solveGlobalIK solves the global inverse kinematics for the given position

Parameters

name
the name of the KBM

Return Value

the proprioception

::Ice::DoubleSeq solveDifferentialIK(string name, ::Ice::DoubleSeq targetPosition, ::Ice::DoubleSeq currentPosition, ::Ice::DoubleSeq currentProprioception, ::Ice::DoubleSeq lowerProprioceptionLimits, ::Ice::DoubleSeq upperProprioceptionLimits)

@brief solveDifferentialIK solves the differential inverse kinematics for the given position

Parameters

name
the name of the KBM

Return Value

the proprioception

void storeToMemory(string kbmName, string nodeSetName, string referenceNodeName, string robotName)

void restoreFromMemory(string name, string nodeSetName, string referenceNodeName, string robotName)

bool isInMemory(string nodeSetName, string referenceNodeName, string robotName)

::Ice::StringSeq kbmNames()

Returns the names of the existing KBMs

void clearAccumulators()

Clears the accumulators


Home Previous Up Next Index