Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs.
More...
#include <kinematic_extension_dof.h>
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()
KinematicExtensionDOF::~KinematicExtensionDOF |
( |
| ) |
|
|
inline |
◆ adjustJacobian()
virtual KDL::Jacobian KinematicExtensionDOF::adjustJacobian |
( |
const KDL::Jacobian & |
jac_chain | ) |
|
|
pure virtual |
◆ adjustJacobianDof()
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_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. |
- 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.
◆ adjustJointStates()
◆ adjustLimiterParams()
◆ initExtension()
virtual bool KinematicExtensionDOF::initExtension |
( |
| ) |
|
|
pure virtual |
◆ processResultExtension()
virtual void KinematicExtensionDOF::processResultExtension |
( |
const KDL::JntArray & |
q_dot_ik | ) |
|
|
pure virtual |
◆ ext_dof_
unsigned int KinematicExtensionDOF::ext_dof_ |
|
protected |
◆ joint_names_
std::vector<std::string> KinematicExtensionDOF::joint_names_ |
|
protected |
◆ joint_states_
◆ limits_acc_
std::vector<double> KinematicExtensionDOF::limits_acc_ |
|
protected |
◆ limits_max_
std::vector<double> KinematicExtensionDOF::limits_max_ |
|
protected |
◆ limits_min_
std::vector<double> KinematicExtensionDOF::limits_min_ |
|
protected |
◆ limits_vel_
std::vector<double> KinematicExtensionDOF::limits_vel_ |
|
protected |
The documentation for this class was generated from the following files: