18 #ifndef COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H 19 #define COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H 25 #include <geometry_msgs/Twist.h> 26 #include <Eigen/Geometry> 77 void baseTwistCallback(
const geometry_msgs::Twist::ConstPtr&
msg);
89 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H
Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs...
std::vector< std::string > joint_names_
JointStates joint_states_
std::vector< double > limits_max_
std::vector< double > limits_min_
~KinematicExtensionBaseActive()
virtual bool initExtension()=0
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)=0
virtual JointStates adjustJointStates(const JointStates &joint_states)=0
std::vector< double > limits_vel_
KDL::Jacobian adjustJacobianDof(const KDL::Jacobian &jac_chain, const KDL::Frame eb_frame_ct, const KDL::Frame cb_frame_eb, const ActiveCartesianDimension active_dim)
Base class for kinematic extensions.
Class implementing a mobile base KinematicExtension with Cartesian DoFs (lin_x, lin_y, rot_z) enabled (i.e. 2D).
ros::Publisher base_vel_pub_
std::vector< double > limits_acc_
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)=0
KinematicExtensionBaseActive(const TwistControllerParams ¶ms)
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)=0
KinematicExtensionDOF(const TwistControllerParams ¶ms)