|
|
The Kinematic B\'ezier Maps. More...
#include <MemoryX/libraries/helpers/KinematicBezierMaps/kbm.h>
Classes | |
| struct | ErrorValuesType |
| Return type of the evaluation (KBM::getErrors()) function providing insight in the statistics of the prediction error. More... | |
Public Types | |
| enum | BBCheckType { INCLUDED = 1 , COVERED = 2 , DISJOINT = 4 , OVERLAPPING = 8 , ALL = 15 } |
Cases for the check of bounding boxes (i.e., an interval ![]() ![]() ![]() | |
| enum | Optimization { STANDARD , PLS } |
| Enum for the preferred optimization method during batch learning. More... | |
Public Member Functions | |
| void | batch (const Matrix &proprioception, const Matrix &shape, Optimization method=KBM::STANDARD, Real threshold=0.0) |
| Implements the batch learning algorithm. | |
| BBCheckType | checkBBox (const Vector &lower, const Vector &upper, Real tolerance=0.0f) const |
| Check whether an interval overlaps the the bounding box of the control points. | |
| void | differentiate () |
| Prepares the calculus of the derivatives. Has to be called alwayes after learning. | |
| void | getBBox (Vector &lower, Vector &upper) |
| Vector | getCenter () const |
| Return the center. | |
| Matrix | getControlNet () const |
| ErrorValuesType | getErrors (const Matrix &proprioception, const Matrix &shape) |
| After learning this function gives various error measures over a given test set.online Proprioception must have the same number of columns (i.e., number of samples) while the rows must match the number of input and output dimensions respectively. | |
| Matrix | getJacobian (const Vector &proprioception) const |
| Computes the partial derivative with respect to a configuration. | |
| int | getNDim () const |
| int | getNDoF () const |
| Get the number of degrees of freedom (DoF). | |
| Real | getOverlappingVolume (const Vector &lower, const Vector &upper) |
| Real | getOverlappingVolumeRatio (const Vector &lower, const Vector &upper, Real targetVolume) |
| Vector | getPartialDerivative (const Vector &proprioception, int iDoF) const |
| Computes a partial derivative with respect to a configuration and the specified degree of freedom. | |
| Vector | getSpreadAngles () const |
| Return the spread angles. | |
| void | getSubdivisedNet (const Vector newCenter, Vector newSpreadAngles, Matrix &resultingControlNet) const |
| Work in progress This method computes the control net of a subdivised KBM instance. | |
| void | getSubdivisedNet (unsigned int dof, Real center, Real newSpreadAngle, Matrix &resultingControlNet) const |
| Makes the subdivision only for one degree of freedom. | |
| Real | getVolume () |
| KBM (const KBM &other) | |
| Copy constructor. | |
| KBM (int nDoF, int dim, Real spreadAngle) | |
| Constructor. | |
| void | online (const Matrix &proprioception, const Matrix &shape, Real learnRate=1.0) |
| Implements the online learning algorithm. | |
| Matrix | predict (const Matrix &proprioception, int dim=0) const |
| Predicts a value of the FK given a set of joint angles. | |
| void | reset () |
| Forgets all previously learned samples. | |
| bool | restore (std::string fileName="") |
| loads a KBM with same input/output dimensions from disk (comma-separated values). | |
| void | store (std::string fileName="") |
| stores the current KBM as a comma-separated matrix to disk. | |
| void | subdivide (const Vector ¢er, const Vector &newSpreadAngles) |
| Work in progress This method subdivides the KBM representation. | |
Static Public Member Functions | |
| static BBCheckType | checkBBoxes (const Vector &lower, const Vector &upper, const Matrix &controlNet, Real tolerance=0.0f) |
| Check whether an interval overlaps the the bounding box of a given control net. | |
| static KBM_ptr | createFromVirtualRobot (VirtualRobot::KinematicChainPtr chain, VirtualRobot::SceneObjectPtr FoR, const Vector &spreadAngles, bool useOrientation=false) |
| static KBM_ptr | createKBM (int nDoF, int dim, const Vector ¢er, const Vector &spreadAngles, const Matrix &controlNet) |
| Factory methods. | |
| static void | getBBox (Vector &lower, Vector &upper, const Matrix &controlNet) |
| Helper function that extracts the bounding box of a control net. | |
The Kinematic B\'ezier Maps.
This class represents the Kinematic B\'ezier Map algorithm. See the unit test on hints on how to use it.
| enum BBCheckType |
Cases for the check of bounding boxes (i.e., an interval ![$ [c_{l,1},c_{u,1}]\times\ldots\times [c_{l,n},c_{u,n}] $](../../form_0.png)

![$ [i_{l,1},i_{u,1}]\times\ldots\times [i_{l,n},i_{u,n}] $](../../form_2.png)
| enum Optimization |
Constructor.
| nDoF | The number of the kinematic chain's degrees of freedom (number of input dimensions) |
| dim | The number of output dimensions (usually three) |
| spreadAngle | The input values should be centered around 0 and this angle should represent their distribution in input space. |
| void batch | ( | const Matrix & | proprioception, |
| const Matrix & | shape, | ||
| Optimization | method = KBM::STANDARD, | ||
| Real | threshold = 0.0 ) |
Implements the batch learning algorithm.
| proprioception | The input values (joint angles) |
| shape | The output values (e.g. 3D TCP positions) |
| method | Select optimization with standard linear least mean squares (KBM::STANDARD) or partial least squares (KMB::PLS) |
| threshold | Models the noise and should equal the expected mean positioning error of the system. Only used with partial least squares (KBM::PLS) Proprioception must have the same number of columns (i.e., number of samples) while the rows must match the number of input and output dimensions respectively. |
Definition at line 213 of file kbm.cpp.
Here is the call graph for this function:| KBM::BBCheckType checkBBox | ( | const Vector & | lower, |
| const Vector & | upper, | ||
| Real | tolerance = 0.0f ) const |
Check whether an interval overlaps the the bounding box of the control points.
| lower | The lower bounds of the interval. |
| upper | The upper bounds of the interval. |
| tolerance | Widens each bounding box by twice this skalar. You should use lower and upper to implement this behavior regularly. |
Definition at line 242 of file inverse.cpp.
Here is the call graph for this function:
|
static |
Check whether an interval overlaps the the bounding box of a given control net.
| lower | The lower bounds of the interval. |
| upper | The upper bounds of the interval. |
| controlNet | Check againt the bounding box of the points defined by the columns of this matrix. |
| tolerance | Widens each bounding box by twice this skalar. You should use lower and upper to implement this behavior regularly. |
Definition at line 248 of file inverse.cpp.
Here is the call graph for this function:
Here is the caller graph for this function:| void differentiate | ( | ) |
Helper function that extracts the bounding box of a control net.
Definition at line 298 of file inverse.cpp.
Here is the caller graph for this function:| KBM::ErrorValuesType getErrors | ( | const Matrix & | proprioception, |
| const Matrix & | shape ) |
| int getNDim | ( | ) | const |
| int getNDoF | ( | ) | const |
Definition at line 327 of file inverse.cpp.
Here is the call graph for this function:
Here is the caller graph for this function:| void getSubdivisedNet | ( | const Vector | newCenter, |
| Vector | newSpreadAngles, | ||
| Matrix & | resultingControlNet ) const |
Work in progress This method computes the control net of a subdivised KBM instance.
| center | The new zero of the input values. |
| newSpreadAngles | The new spread angle vector after subdivision. |
| resultingControlNet | The resulting control net of the subdivised KBM. |
This method computes only the control net (i.e., does not create a new KBM instance). It can be used, for instance, in the global inverse kinematics algorithms.
Definition at line 147 of file inverse.cpp.
Here is the caller graph for this function:| void getSubdivisedNet | ( | unsigned int | dof, |
| Real | center, | ||
| Real | newSpreadAngle, | ||
| Matrix & | resultingControlNet ) const |
Makes the subdivision only for one degree of freedom.
Definition at line 40 of file inverse.cpp.
| Real getVolume | ( | ) |
Implements the online learning algorithm.
| proprioception | The input values (joint angles) |
| shape | The output values (e.g. 3D TCP positions) |
| learnRate | Learning rate between (0,1) Can be called (and still makes sense) after KBM::restore() and KBM::batch() and prior calls to KBM::online(). Proprioception must have the same number of columns (i.e., number of samples) while the rows must match the number of input and output dimensions respectively. |
Definition at line 239 of file kbm.cpp.
Here is the call graph for this function:Predicts a value of the FK given a set of joint angles.
| proprioception | The input values (joint angles in the columns). |
| dim | If > 0, the prediction assumes it is the last joint in the kinematic chain and creates a coordinate frame according to the partial derivative. |
Definition at line 343 of file kbm.cpp.
Here is the caller graph for this function:| bool restore | ( | std::string | fileName = "" | ) |
| void store | ( | std::string | fileName = "" | ) |
Work in progress This method subdivides the KBM representation.
| center | The new zero of the input values. |
| newSpreadAngles | The new spread angle vector after subdivision. It can also be used to increase the original angles. Important: The new spread angles must be smaller than ![]() |
Definition at line 32 of file inverse.cpp.
Here is the call graph for this function: