Simox  2.3.62
VirtualRobot::JacobiProvider Class Referenceabstract
Inheritance diagram for VirtualRobot::JacobiProvider:
VirtualRobot::CoMIK VirtualRobot::Constraint VirtualRobot::DifferentialIK VirtualRobot::JointLimitAvoidanceJacobi

Public Types

enum  InverseJacobiMethod { eSVD, eSVDDamped, eTranspose }
 Several methods are offered for inverting the Jacobi (i.e. building the Pseudoinverse) More...
 

Public Member Functions

 JacobiProvider (RobotNodeSetPtr rns, InverseJacobiMethod invJacMethod=eSVD)
 
virtual ~JacobiProvider ()
 
virtual Eigen::MatrixXf getJacobianMatrix ()=0
 
virtual Eigen::MatrixXd getJacobianMatrixD ()
 
virtual Eigen::MatrixXf getJacobianMatrix (SceneObjectPtr tcp)=0
 
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 ()
 
virtual Eigen::VectorXf getError (float stepSize=1.0f)=0
 
virtual bool checkTolerances ()=0
 
bool isInitialized ()
 
void setJointWeights (const Eigen::VectorXf &jointWeights)
 
virtual void print ()
 print Print current status of the IK solver More...
 
float getDampedSvdLambda () const
 
void setDampedSvdLambda (float value)
 
float getJacobiMMRegularization () const
 
void setJacobiMMRegularization (float value)
 
float getJacobiRadianRegularization () const
 
void setJacobiRadianRegularization (float value)
 

Protected Member Functions

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

std::string name
 
RobotNodeSetPtr rns
 
InverseJacobiMethod inverseMethod
 
bool initialized
 
Eigen::VectorXf jointWeights
 
float dampedSvdLambda
 
float jacobiMMRegularization
 
float jacobiRadianRegularization
 

Member Enumeration Documentation

Several methods are offered for inverting the Jacobi (i.e. building the Pseudoinverse)

Enumerator
eSVD 
eSVDDamped 
eTranspose 

Constructor & Destructor Documentation

VirtualRobot::JacobiProvider::JacobiProvider ( RobotNodeSetPtr  rns,
InverseJacobiMethod  invJacMethod = eSVD 
)
VirtualRobot::JacobiProvider::~JacobiProvider ( )
virtual

Member Function Documentation

virtual bool VirtualRobot::JacobiProvider::checkTolerances ( )
pure virtual
virtual Eigen::MatrixXf VirtualRobot::JacobiProvider::computePseudoInverseJacobianMatrix ( const Eigen::MatrixXf &  m,
const Eigen::VectorXf  regularization = Eigen::VectorXf() 
) const
virtual
virtual Eigen::MatrixXf VirtualRobot::JacobiProvider::computePseudoInverseJacobianMatrix ( const Eigen::MatrixXf &  m,
float  invParameter,
const Eigen::VectorXf  regularization = Eigen::VectorXf() 
) const
virtual
virtual Eigen::MatrixXd VirtualRobot::JacobiProvider::computePseudoInverseJacobianMatrixD ( const Eigen::MatrixXd &  m,
const Eigen::VectorXd  regularization = Eigen::VectorXd() 
) const
virtual
Eigen::MatrixXd VirtualRobot::JacobiProvider::computePseudoInverseJacobianMatrixD ( const Eigen::MatrixXd &  m,
double  invParameter,
const Eigen::VectorXd  regularization = Eigen::VectorXd() 
) const
virtual
float VirtualRobot::JacobiProvider::getDampedSvdLambda ( ) const
virtual Eigen::VectorXf VirtualRobot::JacobiProvider::getError ( float  stepSize = 1.0f)
pure virtual

The error vector. the value depends on the implementation.

Implemented in VirtualRobot::DifferentialIK, VirtualRobot::Constraint, VirtualRobot::CoMIK, and VirtualRobot::JointLimitAvoidanceJacobi.

virtual Eigen::MatrixXf VirtualRobot::JacobiProvider::getJacobianMatrix ( )
pure virtual
virtual Eigen::MatrixXf VirtualRobot::JacobiProvider::getJacobianMatrix ( SceneObjectPtr  tcp)
pure virtual
MatrixXd VirtualRobot::JacobiProvider::getJacobianMatrixD ( )
virtual
MatrixXd VirtualRobot::JacobiProvider::getJacobianMatrixD ( SceneObjectPtr  tcp)
virtual
float VirtualRobot::JacobiProvider::getJacobiMMRegularization ( ) const
float VirtualRobot::JacobiProvider::getJacobiRadianRegularization ( ) const
Eigen::VectorXf VirtualRobot::JacobiProvider::getJacobiRegularization ( IKSolver::CartesianSelection  mode = IKSolver::All)
virtual
Eigen::MatrixXf VirtualRobot::JacobiProvider::getPseudoInverseJacobianMatrix ( const Eigen::VectorXf  regularization = Eigen::VectorXf())
virtual
Eigen::MatrixXf VirtualRobot::JacobiProvider::getPseudoInverseJacobianMatrix ( SceneObjectPtr  tcp,
const Eigen::VectorXf  regularization = Eigen::VectorXf() 
)
virtual
Eigen::MatrixXd VirtualRobot::JacobiProvider::getPseudoInverseJacobianMatrixD ( const Eigen::VectorXd  regularization = Eigen::VectorXd())
virtual
Eigen::MatrixXd VirtualRobot::JacobiProvider::getPseudoInverseJacobianMatrixD ( SceneObjectPtr  tcp,
const Eigen::VectorXd  regularization = Eigen::VectorXd() 
)
virtual
VirtualRobot::RobotNodeSetPtr VirtualRobot::JacobiProvider::getRobotNodeSet ( )
bool VirtualRobot::JacobiProvider::isInitialized ( )
void VirtualRobot::JacobiProvider::print ( )
virtual

print Print current status of the IK solver

Reimplemented in VirtualRobot::DifferentialIK, and VirtualRobot::CoMIK.

void VirtualRobot::JacobiProvider::setDampedSvdLambda ( float  value)
void VirtualRobot::JacobiProvider::setJacobiMMRegularization ( float  value)
void VirtualRobot::JacobiProvider::setJacobiRadianRegularization ( float  value)
void VirtualRobot::JacobiProvider::setJointWeights ( const Eigen::VectorXf &  jointWeights)
void VirtualRobot::JacobiProvider::updatePseudoInverseJacobianMatrix ( Eigen::MatrixXf &  invJac,
const Eigen::MatrixXf &  m,
float  invParameter = 0.0f,
Eigen::VectorXf  regularization = Eigen::VectorXf() 
) const
virtual
void VirtualRobot::JacobiProvider::updatePseudoInverseJacobianMatrixD ( Eigen::MatrixXd &  invJac,
const Eigen::MatrixXd &  m,
double  invParameter = 0.0,
Eigen::VectorXd  regularization = Eigen::VectorXd() 
) const
virtual
void VirtualRobot::JacobiProvider::updatePseudoInverseJacobianMatrixDInternal ( Eigen::MatrixXd &  invJac,
const Eigen::MatrixXd &  m,
double  invParameter = 0.0 
) const
protectedvirtual
void VirtualRobot::JacobiProvider::updatePseudoInverseJacobianMatrixInternal ( Eigen::MatrixXf &  invJac,
const Eigen::MatrixXf &  m,
float  invParameter = 0.0f 
) const
protectedvirtual

Field Documentation

float VirtualRobot::JacobiProvider::dampedSvdLambda
protected
bool VirtualRobot::JacobiProvider::initialized
protected
InverseJacobiMethod VirtualRobot::JacobiProvider::inverseMethod
protected
float VirtualRobot::JacobiProvider::jacobiMMRegularization
protected
float VirtualRobot::JacobiProvider::jacobiRadianRegularization
protected
Eigen::VectorXf VirtualRobot::JacobiProvider::jointWeights
protected
std::string VirtualRobot::JacobiProvider::name
protected
RobotNodeSetPtr VirtualRobot::JacobiProvider::rns
protected