Go to the documentation of this file.
16 #include <Eigen/Eigen>
23 #include <VirtualRobot/Robot.h>
24 #include <VirtualRobot/VirtualRobotException.h>
25 #include <VirtualRobot/Nodes/RobotNode.h>
26 #include <VirtualRobot/KinematicChain.h>
27 #include <VirtualRobot/Nodes/RobotNodeRevolute.h>
30 #define KBM_USE_DOUBLE_PRECISION
32 #define KBM_IMPORT_EXPORT
36 #ifdef KBM_USE_DOUBLE_PRECISION
44 using Matrix = Eigen::MatrixXf;
45 using Vector = Eigen::VectorXf;
47 using Vector3 = Eigen::Vector3f;
131 KBM(
int nDoF,
int dim,
Real spreadAngle);
134 bool restore(std::string fileName =
"");
136 void store(std::string fileName =
"");
146 void online(
const Matrix& proprioception,
const Matrix& shape,
Real learnRate = 1.0);
169 Matrix predict(
const Matrix& proprioception,
int dim = 0)
const;
172 void differentiate();
175 Vector getPartialDerivative(
const Vector& proprioception,
int iDoF)
const;
187 void subdivide(
const Vector& center,
const Vector& newSpreadAngles);
197 void getSubdivisedNet(
const Vector newCenter,
Vector newSpreadAngles,
Matrix& resultingControlNet)
const;
200 void getSubdivisedNet(
unsigned int dof,
Real center,
Real newSpreadAngle,
Matrix& resultingControlNet)
const;
231 Vector getSpreadAngles()
const;
239 Matrix getControlNet()
const;
255 void createIndices();
263 std::vector<Matrix> partialDerivatives;
285 this->
center = kbm->getCenter();
288 kbm->getBBox(BBupper, BBlower);
289 this->
lower = BBlower;
290 this->
upper = BBupper;
Namespace where the Partial Least Squares (PLS-1) solver is defined in.
std::vector< Solution > SolutionSet
std::shared_ptr< KBM > KBM_ptr
Solution(const Vector &_center, const Vector &_spreadAngles, const Vector &_upper, const Vector &_lower, const Models::KBM::BBCheckType &_type)
GlobalIKSemiBreadth(Real _semiBreadthRecursion, int _solutionSelect=Models::KBM::COVERED)
Real IQR
Inerquartile range (50% of all errors): .
Models::KBM::BBCheckType type
void subdivideAngles(Side side, unsigned int recursion, Models::KBM_ptr kbm, Vector ¢er, Vector &spreadAngles)
Subdivides the joint angles only. Can be used to select in which direction to subdivise first.
virtual unsigned int recurse(unsigned int level, Models::KBM_ptr kbm)=0
Real STD
Standard deviation.
Real semiBreadthRecursion
Return type of the evaluation (KBM::getErrors()) function providing insight in the statistics of the ...
std::ostream & operator<<(std::ostream &os, const KBM::ErrorValuesType &et)
Real Median
Median of the error.
@ COVERED
The bounding box is covered by the interval (most interesting case for inverse kinematics).
void store(const mongocxx::database &db, const armem::wm::Memory &m)
Where the model representation for a Body Schema (especially the Kinematic BĀ“ezier Maps) reside.
ReaderT::InputType & input
BBCheckType
Cases for the check of bounding boxes (i.e., an interval ) and an interval ( )both in Cartesian coor...
unsigned int recurse(unsigned int level, Models::KBM_ptr kbm) override
Models::KBM::BBCheckType type
Solution(Models::KBM_ptr kbm, Models::KBM::BBCheckType type)
#define KBM_IMPORT_EXPORT
Finds all solutions to the Global IK.
Namespace for algorithms related to solving the inverse kinematics.
Optimization
Enum for the preferred optimization method during batch learning.
void solveGlobalIK(unsigned int recursion, int side, SolutionSet &solutionSet, Models::KBM_ptr kbm, const Vector &lower, const Vector &upper, Real resolution, Vector spreadAngles, Vector center)
Expands all nets until a resolution has been reached, then search only for a single solution.
MatrixXX< 4, 4, float > Matrix4f
Models::KBM_ptr subdivideKBM(GlobalIKBase::Side side, unsigned int recursion, Models::KBM_ptr kbm)
Subdivides the kbm and creates new KBM. Calls GlobalIKBase::subdivideAngles().
GlobalIKBase::SolutionSet runDijkstra(KBM::Inverse::GraphNode initial)
The Kinematic B\'ezier Maps.
boost::intrusive_ptr< SceneObject > SceneObjectPtr
GraphNode(Models::KBM_ptr _model, Real _ratio, int _level, Real _volume)
void solve(Models::KBM_ptr kbm, const Vector lower, const Vector upper, Real resolution=2.0f *M_PI/180.0f)
unsigned int recurse(unsigned int level, Models::KBM_ptr kbm) override
Solution(const Vector &_center, const Vector &_spreadAngles, const Vector &_upper, const Vector &_lower, const Models::KBM::BBCheckType &_type)
double Real
Type definition of the underlying Realing point type.
std::vector< Solution > SolutionSet
Return type of the global inverse kinematics solvers.
Matrix KBM_IMPORT_EXPORT solve(const Matrix &input, const Matrix output, Real threshold)
Solves a linear system of equations using the partial least squares algorithm.