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

#include <chainiksolvervel_pinv_givens.hpp>

Inheritance diagram for KDL::ChainIkSolverVel_pinv_givens:
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 &, const FrameVel &, JntArrayVel &)
 
 ChainIkSolverVel_pinv_givens (const Chain &chain)
 
virtual void updateInternalDataStructures ()
 
 ~ChainIkSolverVel_pinv_givens ()
 
- Public Member Functions inherited from KDL::ChainIkSolverVel
virtual ~ChainIkSolverVel ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 Return the latest error. More...
 
 SolverI ()
 Initialize latest error to E_NOERROR. More...
 
virtual const char * strError (const int error) const
 
virtual ~SolverI ()
 

Private Attributes

Eigen::MatrixXd B
 
const Chainchain
 
Jacobian jac
 
Eigen::MatrixXd jac_eigen
 
ChainJntToJacSolver jnt2jac
 
unsigned int m
 
unsigned int n
 
unsigned int nj
 
Eigen::VectorXd qdot_eigen
 
Eigen::VectorXd S
 
Eigen::VectorXd SUY
 
Eigen::VectorXd tempi
 
bool toggle
 
bool transpose
 
Eigen::MatrixXd U
 
Eigen::VectorXd UY
 
Eigen::MatrixXd V
 
Eigen::VectorXd v_in_eigen
 

Additional Inherited Members

- Public Types inherited from KDL::SolverI
enum  {
  E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2,
  E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6,
  E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8
}
 
- Protected Attributes inherited from KDL::SolverI
int error
 Latest error, initialized to E_NOERROR in constructor. More...
 

Detailed Description

Implementation of a inverse velocity kinematics algorithm based on the generalize pseudo inverse to calculate the velocity transformation from Cartesian to joint space of a general KDL::Chain. It uses a svd-calculation based on householders rotations.

Definition at line 22 of file chainiksolvervel_pinv_givens.hpp.

Constructor & Destructor Documentation

◆ ChainIkSolverVel_pinv_givens()

KDL::ChainIkSolverVel_pinv_givens::ChainIkSolverVel_pinv_givens ( const Chain chain)
explicit

Constructor of the solver

Parameters
chainthe chain to calculate the inverse velocity kinematics for

Definition at line 27 of file chainiksolvervel_pinv_givens.cpp.

◆ ~ChainIkSolverVel_pinv_givens()

KDL::ChainIkSolverVel_pinv_givens::~ChainIkSolverVel_pinv_givens ( )

Definition at line 65 of file chainiksolvervel_pinv_givens.cpp.

Member Function Documentation

◆ CartToJnt() [1/2]

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

Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities.

Parameters
q_ininput joint positions
v_ininput cartesian velocity
qdot_outoutput joint velocities
Returns
if < 0 something went wrong

Implements KDL::ChainIkSolverVel.

Definition at line 70 of file chainiksolvervel_pinv_givens.cpp.

◆ CartToJnt() [2/2]

virtual int KDL::ChainIkSolverVel_pinv_givens::CartToJnt ( const JntArray ,
const FrameVel ,
JntArrayVel  
)
inlinevirtual

not (yet) implemented.

Implements KDL::ChainIkSolverVel.

Definition at line 41 of file chainiksolvervel_pinv_givens.hpp.

◆ updateInternalDataStructures()

void KDL::ChainIkSolverVel_pinv_givens::updateInternalDataStructures ( )
virtual

Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.

Implements KDL::ChainIkSolverVel.

Definition at line 48 of file chainiksolvervel_pinv_givens.cpp.

Member Data Documentation

◆ B

Eigen::MatrixXd KDL::ChainIkSolverVel_pinv_givens::B
private

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

◆ chain

const Chain& KDL::ChainIkSolverVel_pinv_givens::chain
private

Definition at line 47 of file chainiksolvervel_pinv_givens.hpp.

◆ jac

Jacobian KDL::ChainIkSolverVel_pinv_givens::jac
private

Definition at line 50 of file chainiksolvervel_pinv_givens.hpp.

◆ jac_eigen

Eigen::MatrixXd KDL::ChainIkSolverVel_pinv_givens::jac_eigen
private

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

◆ jnt2jac

ChainJntToJacSolver KDL::ChainIkSolverVel_pinv_givens::jnt2jac
private

Definition at line 49 of file chainiksolvervel_pinv_givens.hpp.

◆ m

unsigned int KDL::ChainIkSolverVel_pinv_givens::m
private

Definition at line 52 of file chainiksolvervel_pinv_givens.hpp.

◆ n

unsigned int KDL::ChainIkSolverVel_pinv_givens::n
private

Definition at line 52 of file chainiksolvervel_pinv_givens.hpp.

◆ nj

unsigned int KDL::ChainIkSolverVel_pinv_givens::nj
private

Definition at line 48 of file chainiksolvervel_pinv_givens.hpp.

◆ qdot_eigen

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_givens::qdot_eigen
private

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

◆ S

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_givens::S
private

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

◆ SUY

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_givens::SUY
private

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

◆ tempi

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_givens::tempi
private

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

◆ toggle

bool KDL::ChainIkSolverVel_pinv_givens::toggle
private

Definition at line 51 of file chainiksolvervel_pinv_givens.hpp.

◆ transpose

bool KDL::ChainIkSolverVel_pinv_givens::transpose
private

Definition at line 51 of file chainiksolvervel_pinv_givens.hpp.

◆ U

Eigen::MatrixXd KDL::ChainIkSolverVel_pinv_givens::U
private

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

◆ UY

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_givens::UY
private

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

◆ V

Eigen::MatrixXd KDL::ChainIkSolverVel_pinv_givens::V
private

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

◆ v_in_eigen

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_givens::v_in_eigen
private

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.


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


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:15