Go to the documentation of this file.
18 #ifndef COB_TWIST_CONTROLLER_CONSTRAINTS_CONSTRAINT_BASE_H
19 #define COB_TWIST_CONTROLLER_CONSTRAINTS_CONSTRAINT_BASE_H
25 #include <boost/shared_ptr.hpp>
26 #include <kdl/jntarray.hpp>
27 #include <kdl/jntarrayvel.hpp>
39 <
typename PRIO = uint32_t>
81 virtual std::string
getTaskId()
const = 0;
95 const Eigen::MatrixXd& homogeneous_solution)
const = 0;
110 <
typename T_PARAMS,
typename PRIO = uint32_t>
147 virtual std::string
getTaskId()
const = 0;
156 return Eigen::MatrixXd::Zero(1, 1);
161 return Eigen::VectorXd::Zero(1, 1);
201 const Eigen::MatrixXd& homogeneous_solution)
const = 0;
229 template <
typename T_PARAMS,
typename PRIO>
234 #endif // COB_TWIST_CONTROLLER_CONSTRAINTS_CONSTRAINT_BASE_H
virtual ConstraintState getState() const
Matrix6Xd_t jacobian_data_
static uint32_t instance_ctr_
virtual double getValue() const
bool operator>(const PriorityBase &other) const
virtual Eigen::VectorXd getPartialValues() const =0
virtual double getDerivativeValue() const =0
uint32_t member_inst_cnt_
virtual std::string getTaskId() const =0
virtual double getValue() const =0
CallbackDataMediator & callback_data_mediator_
virtual double getCriticalValue() const
JointStates joint_states_
void setPriority(PRIO prio)
virtual void calculate()=0
virtual double getActivationGain() const =0
virtual Task_t createTask()
virtual double getActivationGain() const =0
virtual Eigen::VectorXd getTaskDerivatives() const =0
bool operator==(const PriorityBase &other) const
boost::shared_ptr< PriorityBase< uint32_t > > ConstraintBase_t
virtual Eigen::VectorXd getPartialValues() const
ConstraintBase(PRIO prio, T_PARAMS params, CallbackDataMediator &cbdm)
virtual double getSelfMotionMagnitude(const Eigen::MatrixXd &particular_solution, const Eigen::MatrixXd &homogeneous_solution) const =0
double getPriorityAsNum() const
Ensure priority class has overwritten double() operator.
virtual ConstraintState getState() const =0
virtual void update(const JointStates &joint_states, const KDL::JntArrayVel &joints_prediction, const Matrix6Xd_t &jacobian_data)=0
virtual ~ConstraintBase()
KDL::JntArrayVel jnts_prediction_
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6Xd_t
bool operator<(const PriorityBase &other) const
virtual void calculate()=0
virtual void update(const JointStates &joint_states, const KDL::JntArrayVel &joints_prediction, const Matrix6Xd_t &jacobian_data)
virtual Task_t createTask()=0
virtual Eigen::VectorXd getTaskDerivatives() const
virtual double getCriticalValue() const =0
virtual Eigen::MatrixXd getTaskJacobian() const
virtual double getPredictionValue() const
virtual Eigen::MatrixXd getTaskJacobian() const =0
T_PARAMS constraint_params_
virtual std::string getTaskId() const =0
virtual double getPredictionValue() const =0
Eigen::VectorXd partial_values_
virtual double getDerivativeValue() const
virtual double getSelfMotionMagnitude(const Eigen::MatrixXd &particular_solution, const Eigen::MatrixXd &homogeneous_solution) const =0
ros::Time last_pred_time_
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43