Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs. More...
#include <kinematic_extension_dof.h>
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 ¶ms) | |
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_ |
Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs.
Definition at line 32 of file kinematic_extension_dof.h.
KinematicExtensionDOF::KinematicExtensionDOF | ( | const TwistControllerParams & | params | ) | [inline, explicit] |
Definition at line 35 of file kinematic_extension_dof.h.
KinematicExtensionDOF::~KinematicExtensionDOF | ( | ) | [inline] |
Definition at line 39 of file kinematic_extension_dof.h.
virtual KDL::Jacobian KinematicExtensionDOF::adjustJacobian | ( | const KDL::Jacobian & | jac_chain | ) | [pure virtual] |
Implements KinematicExtensionBase.
Implemented in KinematicExtensionBaseActive.
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()'.
jac_chain | The jacobian of the primary kinematic chain. |
eb_frame_ct | The transformation from base_frame of the extension (eb) to the tip_frame of the primary chain (ct). |
cb_frame_eb | The transformation from base_frame of the primary chain (cb) to the base_frame of the extension (eb). |
active_dim | The binary vector of active dimensions. |
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] |
Implements KinematicExtensionBase.
Implemented in KinematicExtensionBaseActive.
virtual LimiterParams KinematicExtensionDOF::adjustLimiterParams | ( | const LimiterParams & | limiter_params | ) | [pure virtual] |
Implements KinematicExtensionBase.
Implemented in KinematicExtensionBaseActive.
virtual bool KinematicExtensionDOF::initExtension | ( | ) | [pure virtual] |
Implements KinematicExtensionBase.
Implemented in KinematicExtensionBaseActive.
virtual void KinematicExtensionDOF::processResultExtension | ( | const KDL::JntArray & | q_dot_ik | ) | [pure virtual] |
Implements KinematicExtensionBase.
Implemented in KinematicExtensionBaseActive.
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.
JointStates KinematicExtensionDOF::joint_states_ [protected] |
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.