Class implementing a mobile base KinematicExtension with Cartesian DoFs (lin_x, lin_y, rot_z) enabled (i.e. 2D). More...
#include <kinematic_extension_dof.h>
Public Member Functions | |
KDL::Jacobian | adjustJacobian (const KDL::Jacobian &jac_chain) |
JointStates | adjustJointStates (const JointStates &joint_states) |
LimiterParams | adjustLimiterParams (const LimiterParams &limiter_params) |
void | baseTwistCallback (const geometry_msgs::Twist::ConstPtr &msg) |
bool | initExtension () |
KinematicExtensionBaseActive (const TwistControllerParams ¶ms) | |
void | processResultExtension (const KDL::JntArray &q_dot_ik) |
~KinematicExtensionBaseActive () | |
Public Member Functions inherited from KinematicExtensionDOF | |
KDL::Jacobian | adjustJacobianDof (const KDL::Jacobian &jac_chain, const KDL::Frame eb_frame_ct, const KDL::Frame cb_frame_eb, const ActiveCartesianDimension active_dim) |
KinematicExtensionDOF (const TwistControllerParams ¶ms) | |
~KinematicExtensionDOF () | |
Public Member Functions inherited from KinematicExtensionBase | |
KinematicExtensionBase (const TwistControllerParams ¶ms) | |
virtual | ~KinematicExtensionBase () |
Private Attributes | |
ros::Publisher | base_vel_pub_ |
double | max_vel_lin_base_ |
double | max_vel_rot_base_ |
double | min_vel_lin_base_ |
double | min_vel_rot_base_ |
Additional Inherited Members | |
Protected Attributes inherited from KinematicExtensionDOF | |
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_ |
Protected Attributes inherited from KinematicExtensionBase | |
ros::NodeHandle | nh_ |
const TwistControllerParams & | params_ |
tf::TransformListener | tf_listener_ |
Class implementing a mobile base KinematicExtension with Cartesian DoFs (lin_x, lin_y, rot_z) enabled (i.e. 2D).
Definition at line 62 of file kinematic_extension_dof.h.
|
inlineexplicit |
Definition at line 65 of file kinematic_extension_dof.h.
|
inline |
Definition at line 69 of file kinematic_extension_dof.h.
|
virtual |
Method adjusting the Jacobian used in inverse differential computation. Enable Cartesian DoFs (lin_x, lin_y, rot_z) considering current transformation to main kinematic chain.
get required transformations
active base can move in lin_x, lin_y and rot_z
Implements KinematicExtensionDOF.
Definition at line 170 of file kinematic_extension_dof.cpp.
|
virtual |
Method adjusting the JointStates used in inverse differential computation and limiters. Fill neutrally.
Implements KinematicExtensionDOF.
Definition at line 212 of file kinematic_extension_dof.cpp.
|
virtual |
Method adjusting the LimiterParams used in limiters. Appends limits for BaseActive
Implements KinematicExtensionDOF.
Definition at line 241 of file kinematic_extension_dof.cpp.
void KinematicExtensionBaseActive::baseTwistCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
|
virtual |
Implements KinematicExtensionDOF.
Definition at line 134 of file kinematic_extension_dof.cpp.
|
virtual |
Method processing the partial result related to the kinematic extension. Publish desired Twist to the 'command' topic of the base.
Implements KinematicExtensionDOF.
Definition at line 264 of file kinematic_extension_dof.cpp.
|
private |
Definition at line 80 of file kinematic_extension_dof.h.
|
private |
Definition at line 84 of file kinematic_extension_dof.h.
|
private |
Definition at line 85 of file kinematic_extension_dof.h.
|
private |
Definition at line 82 of file kinematic_extension_dof.h.
|
private |
Definition at line 83 of file kinematic_extension_dof.h.