|
Simox
2.3.74.0
|
Public Types | |
| enum | InverseJacobiMethod { eSVD, eSVDDamped, eSVDDampedDynamic, 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 |
| VirtualRobot::JacobiProvider::JacobiProvider | ( | RobotNodeSetPtr | rns, |
| InverseJacobiMethod | invJacMethod = eSVD |
||
| ) |
|
virtualdefault |
|
pure virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
| float VirtualRobot::JacobiProvider::getDampedSvdLambda | ( | ) | const |
|
pure virtual |
The error vector. the value depends on the implementation.
Implemented in VirtualRobot::DifferentialIK, VirtualRobot::Constraint, VirtualRobot::CoMIK, and VirtualRobot::JointLimitAvoidanceJacobi.
|
pure virtual |
|
pure virtual |
|
virtual |
|
virtual |
| float VirtualRobot::JacobiProvider::getJacobiMMRegularization | ( | ) | const |
| float VirtualRobot::JacobiProvider::getJacobiRadianRegularization | ( | ) | const |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
| VirtualRobot::RobotNodeSetPtr VirtualRobot::JacobiProvider::getRobotNodeSet | ( | ) |
| bool VirtualRobot::JacobiProvider::isInitialized | ( | ) |
|
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 | ) |
|
virtual |
|
virtual |
|
protectedvirtual |
|
protectedvirtual |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |