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 () | |
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_ |
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.
KinematicExtensionBaseActive::KinematicExtensionBaseActive | ( | const TwistControllerParams & | params | ) | [inline, explicit] |
Definition at line 65 of file kinematic_extension_dof.h.
Definition at line 81 of file kinematic_extension_dof.h.
KDL::Jacobian KinematicExtensionBaseActive::adjustJacobian | ( | const KDL::Jacobian & | jac_chain | ) | [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 163 of file kinematic_extension_dof.cpp.
JointStates KinematicExtensionBaseActive::adjustJointStates | ( | const JointStates & | joint_states | ) | [virtual] |
Method adjusting the JointStates used in inverse differential computation and limiters. Fill neutrally.
Implements KinematicExtensionDOF.
Definition at line 205 of file kinematic_extension_dof.cpp.
LimiterParams KinematicExtensionBaseActive::adjustLimiterParams | ( | const LimiterParams & | limiter_params | ) | [virtual] |
Method adjusting the LimiterParams used in limiters. Appends limits for BaseActive
Implements KinematicExtensionDOF.
Definition at line 234 of file kinematic_extension_dof.cpp.
void KinematicExtensionBaseActive::baseTwistCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
bool KinematicExtensionBaseActive::initExtension | ( | ) | [virtual] |
Implements KinematicExtensionDOF.
Definition at line 134 of file kinematic_extension_dof.cpp.
void KinematicExtensionBaseActive::processResultExtension | ( | const KDL::JntArray & | q_dot_ik | ) | [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 257 of file kinematic_extension_dof.cpp.
Definition at line 92 of file kinematic_extension_dof.h.
double KinematicExtensionBaseActive::max_vel_lin_base_ [private] |
Definition at line 96 of file kinematic_extension_dof.h.
double KinematicExtensionBaseActive::max_vel_rot_base_ [private] |
Definition at line 97 of file kinematic_extension_dof.h.
double KinematicExtensionBaseActive::min_vel_lin_base_ [private] |
Definition at line 94 of file kinematic_extension_dof.h.
double KinematicExtensionBaseActive::min_vel_rot_base_ [private] |
Definition at line 95 of file kinematic_extension_dof.h.