Public Member Functions | Protected Attributes
KinematicExtensionDOF Class Reference

Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs. More...

#include <kinematic_extension_dof.h>

Inheritance diagram for KinematicExtensionDOF:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual KDL::Jacobian adjustJacobian (const KDL::Jacobian &jac_chain)=0
KDL::Jacobian adjustJacobianDof (const KDL::Jacobian &jac_chain, const KDL::Frame eb_frame_ct, const KDL::Frame cb_frame_eb, const ActiveCartesianDimension active_dim)
virtual JointStates adjustJointStates (const JointStates &joint_states)=0
virtual LimiterParams adjustLimiterParams (const LimiterParams &limiter_params)=0
virtual bool initExtension ()=0
 KinematicExtensionDOF (const TwistControllerParams &params)
virtual void processResultExtension (const KDL::JntArray &q_dot_ik)=0
 ~KinematicExtensionDOF ()

Protected Attributes

unsigned int ext_dof_
std::vector< std::string > joint_names_
JointStates joint_states_
std::vector< double > limits_acc_
std::vector< double > limits_max_
std::vector< double > limits_min_
std::vector< double > limits_vel_

Detailed Description

Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs.

Definition at line 32 of file kinematic_extension_dof.h.


Constructor & Destructor Documentation

Definition at line 35 of file kinematic_extension_dof.h.

Definition at line 39 of file kinematic_extension_dof.h.


Member Function Documentation

virtual KDL::Jacobian KinematicExtensionDOF::adjustJacobian ( const KDL::Jacobian jac_chain) [pure virtual]
KDL::Jacobian KinematicExtensionDOF::adjustJacobianDof ( const KDL::Jacobian jac_chain,
const KDL::Frame  eb_frame_ct,
const KDL::Frame  cb_frame_eb,
const ActiveCartesianDimension  active_dim 
)

Helper function adjusting the Jacobian used in inverse differential computation based on the Cartesian DoFs enabled in 'adjustJacobian()'.

Parameters:
jac_chainThe jacobian of the primary kinematic chain.
eb_frame_ctThe transformation from base_frame of the extension (eb) to the tip_frame of the primary chain (ct).
cb_frame_ebThe transformation from base_frame of the primary chain (cb) to the base_frame of the extension (eb).
active_dimThe binary vector of active dimensions.
Returns:
The extended Jacobian

compose jac_full considering kinematical extension

angular velocities

linear velocities

Fill Jacobian column by column

Definition at line 31 of file kinematic_extension_dof.cpp.

virtual JointStates KinematicExtensionDOF::adjustJointStates ( const JointStates joint_states) [pure virtual]
virtual LimiterParams KinematicExtensionDOF::adjustLimiterParams ( const LimiterParams limiter_params) [pure virtual]
virtual bool KinematicExtensionDOF::initExtension ( ) [pure virtual]
virtual void KinematicExtensionDOF::processResultExtension ( const KDL::JntArray q_dot_ik) [pure virtual]

Member Data Documentation

unsigned int KinematicExtensionDOF::ext_dof_ [protected]

Definition at line 50 of file kinematic_extension_dof.h.

std::vector<std::string> KinematicExtensionDOF::joint_names_ [protected]

Definition at line 51 of file kinematic_extension_dof.h.

Definition at line 52 of file kinematic_extension_dof.h.

std::vector<double> KinematicExtensionDOF::limits_acc_ [protected]

Definition at line 56 of file kinematic_extension_dof.h.

std::vector<double> KinematicExtensionDOF::limits_max_ [protected]

Definition at line 53 of file kinematic_extension_dof.h.

std::vector<double> KinematicExtensionDOF::limits_min_ [protected]

Definition at line 54 of file kinematic_extension_dof.h.

std::vector<double> KinematicExtensionDOF::limits_vel_ [protected]

Definition at line 55 of file kinematic_extension_dof.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 Jun 6 2019 21:19:26