Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
ConstraintBase< T_PARAMS, PRIO > Class Template Referenceabstract

#include <constraint_base.h>

Inheritance diagram for ConstraintBase< T_PARAMS, PRIO >:
Inheritance graph
[legend]

Public Member Functions

virtual void calculate ()=0
 
 ConstraintBase (PRIO prio, T_PARAMS params, CallbackDataMediator &cbdm)
 
virtual Task_t createTask ()
 
virtual double getActivationGain () const =0
 
virtual double getDerivativeValue () const
 
virtual Eigen::VectorXd getPartialValues () const
 
virtual double getPredictionValue () const
 
virtual double getSelfMotionMagnitude (const Eigen::MatrixXd &particular_solution, const Eigen::MatrixXd &homogeneous_solution) const =0
 
virtual ConstraintState getState () const
 
virtual Eigen::VectorXd getTaskDerivatives () const
 
virtual std::string getTaskId () const =0
 
virtual Eigen::MatrixXd getTaskJacobian () const
 
virtual double getValue () const
 
virtual void update (const JointStates &joint_states, const KDL::JntArrayVel &joints_prediction, const Matrix6Xd_t &jacobian_data)
 
virtual ~ConstraintBase ()
 
- Public Member Functions inherited from PriorityBase< PRIO >
PRIO getPriority () const
 
double getPriorityAsNum () const
 Ensure priority class has overwritten double() operator. More...
 
bool operator< (const PriorityBase &other) const
 
bool operator== (const PriorityBase &other) const
 
bool operator> (const PriorityBase &other) const
 
 PriorityBase (PRIO prio)
 
void setPriority (PRIO prio)
 
virtual ~PriorityBase ()
 

Protected Member Functions

virtual double getCriticalValue () const
 

Protected Attributes

CallbackDataMediatorcallback_data_mediator_
 
T_PARAMS constraint_params_
 
double derivative_value_
 
Matrix6Xd_t jacobian_data_
 
KDL::JntArrayVel jnts_prediction_
 
JointStates joint_states_
 
ros::Time last_pred_time_
 
ros::Time last_time_
 
double last_value_
 
uint32_t member_inst_cnt_
 
Eigen::VectorXd partial_values_
 
double prediction_value_
 
ConstraintState state_
 
double value_
 
- Protected Attributes inherited from PriorityBase< PRIO >
PRIO priority_
 

Static Protected Attributes

static uint32_t instance_ctr_ = 0
 

Detailed Description

template<typename T_PARAMS, typename PRIO = uint32_t>
class ConstraintBase< T_PARAMS, PRIO >

Base class for all derived constraints. Used to represent a common data structure for all concrete constraints.

Template Parameters
T_PARAMSA specific constraint parameter class.
PRIOSee base class.

Definition at line 111 of file constraint_base.h.

Constructor & Destructor Documentation

template<typename T_PARAMS , typename PRIO = uint32_t>
ConstraintBase< T_PARAMS, PRIO >::ConstraintBase ( PRIO  prio,
T_PARAMS  params,
CallbackDataMediator cbdm 
)
inline
Parameters
prioA priority value / object.
qThe joint states.
paramsThe parameters for the constraint to parameterize the calculation of the cost function values.

Definition at line 119 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual ConstraintBase< T_PARAMS, PRIO >::~ConstraintBase ( )
inlinevirtual

Definition at line 135 of file constraint_base.h.

Member Function Documentation

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual void ConstraintBase< T_PARAMS, PRIO >::calculate ( )
pure virtual
template<typename T_PARAMS , typename PRIO = uint32_t>
virtual Task_t ConstraintBase< T_PARAMS, PRIO >::createTask ( )
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 138 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual double ConstraintBase< T_PARAMS, PRIO >::getActivationGain ( ) const
pure virtual
template<typename T_PARAMS , typename PRIO = uint32_t>
virtual double ConstraintBase< T_PARAMS, PRIO >::getCriticalValue ( ) const
inlineprotectedvirtual

Implements PriorityBase< PRIO >.

Reimplemented in CollisionAvoidance< T_PARAMS, PRIO >.

Definition at line 223 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual double ConstraintBase< T_PARAMS, PRIO >::getDerivativeValue ( ) const
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 184 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual Eigen::VectorXd ConstraintBase< T_PARAMS, PRIO >::getPartialValues ( ) const
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 189 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual double ConstraintBase< T_PARAMS, PRIO >::getPredictionValue ( ) const
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 194 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual double ConstraintBase< T_PARAMS, PRIO >::getSelfMotionMagnitude ( const Eigen::MatrixXd &  particular_solution,
const Eigen::MatrixXd &  homogeneous_solution 
) const
pure virtual
template<typename T_PARAMS , typename PRIO = uint32_t>
virtual ConstraintState ConstraintBase< T_PARAMS, PRIO >::getState ( ) const
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 149 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual Eigen::VectorXd ConstraintBase< T_PARAMS, PRIO >::getTaskDerivatives ( ) const
inlinevirtual
template<typename T_PARAMS , typename PRIO = uint32_t>
virtual std::string ConstraintBase< T_PARAMS, PRIO >::getTaskId ( ) const
pure virtual
template<typename T_PARAMS , typename PRIO = uint32_t>
virtual Eigen::MatrixXd ConstraintBase< T_PARAMS, PRIO >::getTaskJacobian ( ) const
inlinevirtual
template<typename T_PARAMS , typename PRIO = uint32_t>
virtual double ConstraintBase< T_PARAMS, PRIO >::getValue ( ) const
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 179 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
virtual void ConstraintBase< T_PARAMS, PRIO >::update ( const JointStates joint_states,
const KDL::JntArrayVel joints_prediction,
const Matrix6Xd_t jacobian_data 
)
inlinevirtual

Implements PriorityBase< PRIO >.

Definition at line 164 of file constraint_base.h.

Member Data Documentation

template<typename T_PARAMS , typename PRIO = uint32_t>
CallbackDataMediator& ConstraintBase< T_PARAMS, PRIO >::callback_data_mediator_
protected

Definition at line 206 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
T_PARAMS ConstraintBase< T_PARAMS, PRIO >::constraint_params_
protected

Definition at line 205 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double ConstraintBase< T_PARAMS, PRIO >::derivative_value_
protected

Definition at line 213 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
uint32_t ConstraintBase< T_PARAMS, PRIO >::instance_ctr_ = 0
staticprotected

Definition at line 221 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
Matrix6Xd_t ConstraintBase< T_PARAMS, PRIO >::jacobian_data_
protected

Definition at line 210 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
KDL::JntArrayVel ConstraintBase< T_PARAMS, PRIO >::jnts_prediction_
protected

Definition at line 209 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
JointStates ConstraintBase< T_PARAMS, PRIO >::joint_states_
protected

Definition at line 208 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
ros::Time ConstraintBase< T_PARAMS, PRIO >::last_pred_time_
protected

Definition at line 218 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
ros::Time ConstraintBase< T_PARAMS, PRIO >::last_time_
protected

Definition at line 217 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double ConstraintBase< T_PARAMS, PRIO >::last_value_
protected

Definition at line 216 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
uint32_t ConstraintBase< T_PARAMS, PRIO >::member_inst_cnt_
protected

Definition at line 220 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
Eigen::VectorXd ConstraintBase< T_PARAMS, PRIO >::partial_values_
protected

Definition at line 214 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double ConstraintBase< T_PARAMS, PRIO >::prediction_value_
protected

Definition at line 215 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
ConstraintState ConstraintBase< T_PARAMS, PRIO >::state_
protected

Definition at line 204 of file constraint_base.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double ConstraintBase< T_PARAMS, PRIO >::value_
protected

Definition at line 212 of file constraint_base.h.


The documentation for this class was generated from the following file:


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:01