Simox  2.3.62
VirtualRobot::CoMIK Class Reference
Inheritance diagram for VirtualRobot::CoMIK:

Public Member Functions

 CoMIK (RobotNodeSetPtr rnsJoints, RobotNodeSetPtr rnsBodies, RobotNodePtr coordSystem=RobotNodePtr(), int dimensions=2)
void setGoal (const Eigen::VectorXf &goal, float tolerance=5.0f)
Eigen::MatrixXf getJacobianOfCoM (RobotNodePtr node)
virtual Eigen::MatrixXf getJacobianMatrix ()
virtual Eigen::MatrixXf getJacobianMatrix (SceneObjectPtr tcp)
virtual Eigen::VectorXf getError (float stepSize=1.0f)
Eigen::VectorXf computeStep (float stepSize)
bool computeSteps (float stepSize, float minumChange, int maxNStep)
void convertModelScalingtoM (bool enable)
 convertModelScalingtoM If set to true, the Jacobian is computed in meters (instead MM) More...
bool isValid (const Eigen::VectorXf &v) const
virtual bool checkTolerances ()
void checkImprovements (bool enable)
bool solveIK (float stepSize=0.2f, float minChange=0.0f, int maxSteps=50)
virtual void print ()
 print Print current status of the IK solver More...
- Public Member Functions inherited from VirtualRobot::JacobiProvider
 JacobiProvider (RobotNodeSetPtr rns, InverseJacobiMethod invJacMethod=eSVD)
virtual ~JacobiProvider ()
virtual Eigen::MatrixXd getJacobianMatrixD ()
virtual Eigen::MatrixXd getJacobianMatrixD (SceneObjectPtr tcp)
virtual Eigen::MatrixXf computePseudoInverseJacobianMatrix (const Eigen::MatrixXf &m, const Eigen::VectorXf regularization=Eigen::VectorXf()) const
virtual Eigen::MatrixXd computePseudoInverseJacobianMatrixD (const Eigen::MatrixXd &m, const Eigen::VectorXd regularization=Eigen::VectorXd()) const
virtual Eigen::MatrixXf computePseudoInverseJacobianMatrix (const Eigen::MatrixXf &m, float invParameter, const Eigen::VectorXf regularization=Eigen::VectorXf()) const
virtual Eigen::MatrixXd computePseudoInverseJacobianMatrixD (const Eigen::MatrixXd &m, double invParameter, const Eigen::VectorXd regularization=Eigen::VectorXd()) const
virtual void updatePseudoInverseJacobianMatrix (Eigen::MatrixXf &invJac, const Eigen::MatrixXf &m, float invParameter=0.0f, Eigen::VectorXf regularization=Eigen::VectorXf()) const
virtual void updatePseudoInverseJacobianMatrixD (Eigen::MatrixXd &invJac, const Eigen::MatrixXd &m, double invParameter=0.0, Eigen::VectorXd regularization=Eigen::VectorXd()) const
virtual Eigen::MatrixXf getPseudoInverseJacobianMatrix (const Eigen::VectorXf regularization=Eigen::VectorXf())
virtual Eigen::MatrixXd getPseudoInverseJacobianMatrixD (const Eigen::VectorXd regularization=Eigen::VectorXd())
virtual Eigen::MatrixXf getPseudoInverseJacobianMatrix (SceneObjectPtr tcp, const Eigen::VectorXf regularization=Eigen::VectorXf())
virtual Eigen::MatrixXd getPseudoInverseJacobianMatrixD (SceneObjectPtr tcp, const Eigen::VectorXd regularization=Eigen::VectorXd())
virtual Eigen::VectorXf getJacobiRegularization (IKSolver::CartesianSelection mode=IKSolver::All)
VirtualRobot::RobotNodeSetPtr getRobotNodeSet ()
bool isInitialized ()
void setJointWeights (const Eigen::VectorXf &jointWeights)
float getDampedSvdLambda () const
void setDampedSvdLambda (float value)
float getJacobiMMRegularization () const
void setJacobiMMRegularization (float value)
float getJacobiRadianRegularization () const
void setJacobiRadianRegularization (float value)

Additional Inherited Members

- Public Types inherited from VirtualRobot::JacobiProvider
enum  InverseJacobiMethod { eSVD, eSVDDamped, eTranspose }
 Several methods are offered for inverting the Jacobi (i.e. building the Pseudoinverse) More...
- Protected Member Functions inherited from VirtualRobot::JacobiProvider
virtual void updatePseudoInverseJacobianMatrixInternal (Eigen::MatrixXf &invJac, const Eigen::MatrixXf &m, float invParameter=0.0f) const
virtual void updatePseudoInverseJacobianMatrixDInternal (Eigen::MatrixXd &invJac, const Eigen::MatrixXd &m, double invParameter=0.0) const
- Protected Attributes inherited from VirtualRobot::JacobiProvider
std::string name
RobotNodeSetPtr rns
InverseJacobiMethod inverseMethod
bool initialized
Eigen::VectorXf jointWeights
float dampedSvdLambda
float jacobiMMRegularization
float jacobiRadianRegularization

Constructor & Destructor Documentation

VirtualRobot::CoMIK::CoMIK ( RobotNodeSetPtr  rnsJoints,
RobotNodeSetPtr  rnsBodies,
RobotNodePtr  coordSystem = RobotNodePtr(),
int  dimensions = 2 

Initialize with a rns that contains joints and one that contains the bodies.

Member Function Documentation

void VirtualRobot::CoMIK::checkImprovements ( bool  enable)
bool VirtualRobot::CoMIK::checkTolerances ( )
Eigen::VectorXf VirtualRobot::CoMIK::computeStep ( float  stepSize)
bool VirtualRobot::CoMIK::computeSteps ( float  stepSize,
float  minumChange,
int  maxNStep 
void VirtualRobot::CoMIK::convertModelScalingtoM ( bool  enable)

convertModelScalingtoM If set to true, the Jacobian is computed in meters (instead MM)

Eigen::VectorXf VirtualRobot::CoMIK::getError ( float  stepSize = 1.0f)

The error vector. the value depends on the implementation.

Implements VirtualRobot::JacobiProvider.

Eigen::MatrixXf VirtualRobot::CoMIK::getJacobianMatrix ( )
Eigen::MatrixXf VirtualRobot::CoMIK::getJacobianMatrix ( SceneObjectPtr  tcp)
Eigen::MatrixXf VirtualRobot::CoMIK::getJacobianOfCoM ( RobotNodePtr  node)
bool VirtualRobot::CoMIK::isValid ( const Eigen::VectorXf &  v) const
void VirtualRobot::CoMIK::print ( )

print Print current status of the IK solver

Reimplemented from VirtualRobot::JacobiProvider.

void VirtualRobot::CoMIK::setGoal ( const Eigen::VectorXf &  goal,
float  tolerance = 5.0f 
bool VirtualRobot::CoMIK::solveIK ( float  stepSize = 0.2f,
float  minChange = 0.0f,
int  maxSteps = 50