Public Member Functions | Private Attributes | List of all members
KDL::ChainIkSolverVel_wdls_coupling Class Reference

#include <chainiksolvervel_wdls_coupling.hpp>

Inheritance diagram for KDL::ChainIkSolverVel_wdls_coupling:
Inheritance graph
[legend]

Public Member Functions

virtual int CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
 
virtual int CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)
 
 ChainIkSolverVel_wdls_coupling (const Chain_coupling &chain, double eps=0.00001, int maxiter=150)
 
Eigen::MatrixXd getWeightJS ()
 
Eigen::MatrixXd getWeightTS ()
 
void setLambda (const double &lambda)
 
void setWeightJS (const Eigen::MatrixXd &Mq)
 
void setWeightTS (const Eigen::MatrixXd &Mx)
 
virtual void updateInternalDataStructures ()
 
 ~ChainIkSolverVel_wdls_coupling ()
 
- Public Member Functions inherited from KDL::ChainIkSolverVel
virtual ~ChainIkSolverVel ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 
 SolverI ()
 
virtual const char * strError (const int error) const
 
virtual ~SolverI ()
 

Private Attributes

Chain_coupling chain
 
double eps
 
Jacobian jac
 
ChainJntToJacSolver_coupling jnt2jac
 
double lambda
 
int maxiter
 
Eigen::VectorXd S
 
Eigen::VectorXd tmp
 
Eigen::MatrixXd tmp_jac
 
Eigen::MatrixXd tmp_jac_weight1
 
Eigen::MatrixXd tmp_jac_weight2
 
Eigen::MatrixXd tmp_js
 
Eigen::MatrixXd tmp_ts
 
Eigen::MatrixXd U
 
Eigen::MatrixXd V
 
Eigen::MatrixXd weight_js
 
Eigen::MatrixXd weight_ts
 

Additional Inherited Members

- Public Attributes inherited from KDL::SolverI
 E_DEGRADED
 
 E_MAX_ITERATIONS_EXCEEDED
 
 E_NO_CONVERGE
 
 E_NOERROR
 
 E_NOT_IMPLEMENTED
 
 E_NOT_UP_TO_DATE
 
 E_OUT_OF_RANGE
 
 E_SIZE_MISMATCH
 
 E_SVD_FAILED
 
 E_UNDEFINED
 
- Protected Attributes inherited from KDL::SolverI
int error
 

Detailed Description

Definition at line 66 of file chainiksolvervel_wdls_coupling.hpp.

Constructor & Destructor Documentation

◆ ChainIkSolverVel_wdls_coupling()

KDL::ChainIkSolverVel_wdls_coupling::ChainIkSolverVel_wdls_coupling ( const Chain_coupling chain,
double  eps = 0.00001,
int  maxiter = 150 
)
explicit

Definition at line 31 of file chainiksolvervel_wdls_coupling.cpp.

◆ ~ChainIkSolverVel_wdls_coupling()

KDL::ChainIkSolverVel_wdls_coupling::~ChainIkSolverVel_wdls_coupling ( )

Definition at line 53 of file chainiksolvervel_wdls_coupling.cpp.

Member Function Documentation

◆ CartToJnt() [1/2]

int KDL::ChainIkSolverVel_wdls_coupling::CartToJnt ( const JntArray q_in,
const Twist v_in,
JntArray qdot_out 
)
virtual

Implements KDL::ChainIkSolverVel.

Definition at line 82 of file chainiksolvervel_wdls_coupling.cpp.

◆ CartToJnt() [2/2]

virtual int KDL::ChainIkSolverVel_wdls_coupling::CartToJnt ( const JntArray q_init,
const FrameVel v_in,
JntArrayVel q_out 
)
inlinevirtual

Implements KDL::ChainIkSolverVel.

Definition at line 93 of file chainiksolvervel_wdls_coupling.hpp.

◆ getWeightJS()

MatrixXd KDL::ChainIkSolverVel_wdls_coupling::getWeightJS ( )

Definition at line 62 of file chainiksolvervel_wdls_coupling.cpp.

◆ getWeightTS()

MatrixXd KDL::ChainIkSolverVel_wdls_coupling::getWeightTS ( )

Definition at line 72 of file chainiksolvervel_wdls_coupling.cpp.

◆ setLambda()

void KDL::ChainIkSolverVel_wdls_coupling::setLambda ( const double &  lambda)

Definition at line 77 of file chainiksolvervel_wdls_coupling.cpp.

◆ setWeightJS()

void KDL::ChainIkSolverVel_wdls_coupling::setWeightJS ( const Eigen::MatrixXd &  Mq)

/* Set the joint space weighting matrix

Parameters
weight_jsjoint space weighting symetric matrix, default : identity. M_q : This matrix being used as a weight for the norm of the joint space speed it HAS TO BE symmetric and positive definite. We can actually deal with matrices containing a symmetric and positive definite block and 0s otherwise. Taking a diagonal matrix as an example, a 0 on the diagonal means that the corresponding joints will not contribute to the motion of the system. On the other hand, the bigger the value, the most the corresponding joint will contribute to the overall motion. The obtained solution q_dot will actually minimize the weighted norm sqrt(q_dot'*(M_q^-2)*q_dot). In the special case we deal with, it does not make sense to invert M_q but what is important is the physical meaning of all this : a joint that has a zero weight in M_q will not contribute to the motion of the system and this is equivalent to saying that it gets an infinite weight in the norm computation. For more detailed explanation : vince.nosp@m.nt.p.nosp@m.adois.nosp@m.@upm.nosp@m.c.fr

Definition at line 57 of file chainiksolvervel_wdls_coupling.cpp.

◆ setWeightTS()

void KDL::ChainIkSolverVel_wdls_coupling::setWeightTS ( const Eigen::MatrixXd &  Mx)

Definition at line 67 of file chainiksolvervel_wdls_coupling.cpp.

◆ updateInternalDataStructures()

virtual void KDL::ChainIkSolverVel_wdls_coupling::updateInternalDataStructures ( )
inlinevirtual

Implements KDL::ChainIkSolverVel.

Definition at line 98 of file chainiksolvervel_wdls_coupling.hpp.

Member Data Documentation

◆ chain

Chain_coupling KDL::ChainIkSolverVel_wdls_coupling::chain
private

Definition at line 160 of file chainiksolvervel_wdls_coupling.hpp.

◆ eps

double KDL::ChainIkSolverVel_wdls_coupling::eps
private

Definition at line 166 of file chainiksolvervel_wdls_coupling.hpp.

◆ jac

Jacobian KDL::ChainIkSolverVel_wdls_coupling::jac
private

Definition at line 162 of file chainiksolvervel_wdls_coupling.hpp.

◆ jnt2jac

ChainJntToJacSolver_coupling KDL::ChainIkSolverVel_wdls_coupling::jnt2jac
private

Definition at line 161 of file chainiksolvervel_wdls_coupling.hpp.

◆ lambda

double KDL::ChainIkSolverVel_wdls_coupling::lambda
private

Definition at line 176 of file chainiksolvervel_wdls_coupling.hpp.

◆ maxiter

int KDL::ChainIkSolverVel_wdls_coupling::maxiter
private

Definition at line 167 of file chainiksolvervel_wdls_coupling.hpp.

◆ S

Eigen::VectorXd KDL::ChainIkSolverVel_wdls_coupling::S
private

Definition at line 164 of file chainiksolvervel_wdls_coupling.hpp.

◆ tmp

Eigen::VectorXd KDL::ChainIkSolverVel_wdls_coupling::tmp
private

Definition at line 168 of file chainiksolvervel_wdls_coupling.hpp.

◆ tmp_jac

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::tmp_jac
private

Definition at line 169 of file chainiksolvervel_wdls_coupling.hpp.

◆ tmp_jac_weight1

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::tmp_jac_weight1
private

Definition at line 170 of file chainiksolvervel_wdls_coupling.hpp.

◆ tmp_jac_weight2

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::tmp_jac_weight2
private

Definition at line 171 of file chainiksolvervel_wdls_coupling.hpp.

◆ tmp_js

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::tmp_js
private

Definition at line 173 of file chainiksolvervel_wdls_coupling.hpp.

◆ tmp_ts

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::tmp_ts
private

Definition at line 172 of file chainiksolvervel_wdls_coupling.hpp.

◆ U

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::U
private

Definition at line 163 of file chainiksolvervel_wdls_coupling.hpp.

◆ V

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::V
private

Definition at line 165 of file chainiksolvervel_wdls_coupling.hpp.

◆ weight_js

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::weight_js
private

Definition at line 175 of file chainiksolvervel_wdls_coupling.hpp.

◆ weight_ts

Eigen::MatrixXd KDL::ChainIkSolverVel_wdls_coupling::weight_ts
private

Definition at line 174 of file chainiksolvervel_wdls_coupling.hpp.


The documentation for this class was generated from the following files:


kdl_coupling
Author(s): Juan Antonio Corrales Ramon (UPMC)
autogenerated on Mon Feb 28 2022 23:51:59