Go to the documentation of this file.
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>
42 virtual KDL::Jacobian
adjustJacobian(
const KDL::Jacobian& jac_chain) = 0;
89 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H
Base class for kinematic extensions.
KinematicExtensionBaseActive(const TwistControllerParams ¶ms)
std::vector< double > limits_acc_
KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
KinematicExtensionDOF(const TwistControllerParams ¶ms)
void processResultExtension(const KDL::JntArray &q_dot_ik)
virtual bool initExtension()=0
Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs.
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)=0
LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
JointStates adjustJointStates(const JointStates &joint_states)
std::vector< double > limits_max_
std::vector< std::string > joint_names_
~KinematicExtensionBaseActive()
void baseTwistCallback(const geometry_msgs::Twist::ConstPtr &msg)
virtual JointStates adjustJointStates(const JointStates &joint_states)=0
std::vector< double > limits_min_
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)=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 LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)=0
Class implementing a mobile base KinematicExtension with Cartesian DoFs (lin_x, lin_y,...
ros::Publisher base_vel_pub_
JointStates joint_states_
std::vector< double > limits_vel_
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43