Public Member Functions | Private Attributes | List of all members
InverseDifferentialKinematicsSolver Class Reference

#include <inverse_differential_kinematics_solver.h>

Public Member Functions

virtual int CartToJnt (const JointStates &joint_states, const KDL::Twist &v_in, KDL::JntArray &qdot_out)
 
 InverseDifferentialKinematicsSolver (const TwistControllerParams &params, const KDL::Chain &chain, CallbackDataMediator &data_mediator)
 
bool resetAll (TwistControllerParams params)
 
virtual ~InverseDifferentialKinematicsSolver ()
 

Private Attributes

CallbackDataMediatorcallback_data_mediator_
 
const KDL::Chain chain_
 
ConstraintSolverFactory constraint_solver_factory_
 
KDL::ChainFkSolverVel_recursive fk_solver_vel_
 
KDL::Jacobian jac_
 
KDL::ChainJntToJacSolver jnt2jac_
 
boost::shared_ptr< KinematicExtensionBasekinematic_extension_
 
LimiterParams limiter_params_
 
boost::shared_ptr< LimiterContainerlimiters_
 
TwistControllerParams params_
 
TaskStackController_t task_stack_controller_
 

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 42 of file inverse_differential_kinematics_solver.h.

Constructor & Destructor Documentation

InverseDifferentialKinematicsSolver::InverseDifferentialKinematicsSolver ( const TwistControllerParams params,
const KDL::Chain chain,
CallbackDataMediator data_mediator 
)
inline

Constructor of the solver

Parameters
chainthe chain to calculate the inverse velocity kinematics for

Definition at line 52 of file inverse_differential_kinematics_solver.h.

virtual InverseDifferentialKinematicsSolver::~InverseDifferentialKinematicsSolver ( )
inlinevirtual

Definition at line 69 of file inverse_differential_kinematics_solver.h.

Member Function Documentation

int InverseDifferentialKinematicsSolver::CartToJnt ( const JointStates joint_states,
const KDL::Twist v_in,
KDL::JntArray qdot_out 
)
virtual

CartToJnt for chain using SVD considering KinematicExtensions and various DampingMethods

Solve the inverse kinematics problem at the first order differential level.

Let the ChainJntToJacSolver calculate the jacobian "jac_chain" for the current joint positions "q_in"

append columns to Jacobian in order to reflect additional DoFs of kinematical extension

apply input limiters for limiting Cartesian velocities (input Twist)

convert output

output limiters shut be applied here in order to be able to consider the additional DoFs within "AllLimit", too

process result for kinematical extension

then qdot_out shut be resized to contain only the chain_qdot_out's again

Definition at line 27 of file inverse_differential_kinematics_solver.cpp.

bool InverseDifferentialKinematicsSolver::resetAll ( TwistControllerParams  params)

Definition at line 88 of file inverse_differential_kinematics_solver.cpp.

Member Data Documentation

CallbackDataMediator& InverseDifferentialKinematicsSolver::callback_data_mediator_
private

Definition at line 89 of file inverse_differential_kinematics_solver.h.

const KDL::Chain InverseDifferentialKinematicsSolver::chain_
private

Definition at line 83 of file inverse_differential_kinematics_solver.h.

ConstraintSolverFactory InverseDifferentialKinematicsSolver::constraint_solver_factory_
private

Definition at line 92 of file inverse_differential_kinematics_solver.h.

KDL::ChainFkSolverVel_recursive InverseDifferentialKinematicsSolver::fk_solver_vel_
private

Definition at line 85 of file inverse_differential_kinematics_solver.h.

KDL::Jacobian InverseDifferentialKinematicsSolver::jac_
private

Definition at line 84 of file inverse_differential_kinematics_solver.h.

KDL::ChainJntToJacSolver InverseDifferentialKinematicsSolver::jnt2jac_
private

Definition at line 86 of file inverse_differential_kinematics_solver.h.

boost::shared_ptr<KinematicExtensionBase> InverseDifferentialKinematicsSolver::kinematic_extension_
private

Definition at line 91 of file inverse_differential_kinematics_solver.h.

LimiterParams InverseDifferentialKinematicsSolver::limiter_params_
private

Definition at line 88 of file inverse_differential_kinematics_solver.h.

boost::shared_ptr<LimiterContainer> InverseDifferentialKinematicsSolver::limiters_
private

Definition at line 90 of file inverse_differential_kinematics_solver.h.

TwistControllerParams InverseDifferentialKinematicsSolver::params_
private

Definition at line 87 of file inverse_differential_kinematics_solver.h.

TaskStackController_t InverseDifferentialKinematicsSolver::task_stack_controller_
private

Definition at line 94 of file inverse_differential_kinematics_solver.h.


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


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:01