Public Member Functions | Protected Member Functions | Protected Attributes
PriorityBase< PRIO > Class Template Reference

#include <constraint_base.h>

Inheritance diagram for PriorityBase< PRIO >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void calculate ()=0
virtual Task_t createTask ()=0
virtual double getActivationGain () const =0
virtual double getDerivativeValue () const =0
virtual Eigen::VectorXd getPartialValues () const =0
virtual double getPredictionValue () const =0
PRIO getPriority () const
double getPriorityAsNum () const
 Ensure priority class has overwritten double() operator.
virtual double getSelfMotionMagnitude (const Eigen::MatrixXd &particular_solution, const Eigen::MatrixXd &homogeneous_solution) const =0
virtual ConstraintState getState () const =0
virtual Eigen::VectorXd getTaskDerivatives () const =0
virtual std::string getTaskId () const =0
virtual Eigen::MatrixXd getTaskJacobian () const =0
virtual double getValue () const =0
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 void update (const JointStates &joint_states, const KDL::JntArrayVel &joints_prediction, const Matrix6Xd_t &jacobian_data)=0
virtual ~PriorityBase ()

Protected Member Functions

virtual double getCriticalValue () const =0

Protected Attributes

PRIO priority_

Detailed Description

template<typename PRIO = uint32_t>
class PriorityBase< PRIO >

Main base class for all derived constraints. Used to create abstract containers that can be filled with concrete constraints.

Template Parameters:
PRIOA priority class that has operators <, > and == for comparison overridden. To return the priority as a computable double it must override "operator double() const"! Default uint comparison.

Definition at line 40 of file constraint_base.h.


Constructor & Destructor Documentation

template<typename PRIO = uint32_t>
PriorityBase< PRIO >::PriorityBase ( PRIO  prio) [inline, explicit]

Definition at line 43 of file constraint_base.h.

template<typename PRIO = uint32_t>
virtual PriorityBase< PRIO >::~PriorityBase ( ) [inline, virtual]

Definition at line 46 of file constraint_base.h.


Member Function Documentation

template<typename PRIO = uint32_t>
virtual void PriorityBase< PRIO >::calculate ( ) [pure virtual]
template<typename PRIO = uint32_t>
virtual Task_t PriorityBase< PRIO >::createTask ( ) [pure virtual]
template<typename PRIO = uint32_t>
virtual double PriorityBase< PRIO >::getActivationGain ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual double PriorityBase< PRIO >::getCriticalValue ( ) const [protected, pure virtual]
template<typename PRIO = uint32_t>
virtual double PriorityBase< PRIO >::getDerivativeValue ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual Eigen::VectorXd PriorityBase< PRIO >::getPartialValues ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual double PriorityBase< PRIO >::getPredictionValue ( ) const [pure virtual]
template<typename PRIO = uint32_t>
PRIO PriorityBase< PRIO >::getPriority ( ) const [inline]

Definition at line 69 of file constraint_base.h.

template<typename PRIO = uint32_t>
double PriorityBase< PRIO >::getPriorityAsNum ( ) const [inline]

Ensure priority class has overwritten double() operator.

Definition at line 75 of file constraint_base.h.

template<typename PRIO = uint32_t>
virtual double PriorityBase< PRIO >::getSelfMotionMagnitude ( const Eigen::MatrixXd &  particular_solution,
const Eigen::MatrixXd &  homogeneous_solution 
) const [pure virtual]
template<typename PRIO = uint32_t>
virtual ConstraintState PriorityBase< PRIO >::getState ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual Eigen::VectorXd PriorityBase< PRIO >::getTaskDerivatives ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual std::string PriorityBase< PRIO >::getTaskId ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual Eigen::MatrixXd PriorityBase< PRIO >::getTaskJacobian ( ) const [pure virtual]
template<typename PRIO = uint32_t>
virtual double PriorityBase< PRIO >::getValue ( ) const [pure virtual]
template<typename PRIO = uint32_t>
bool PriorityBase< PRIO >::operator< ( const PriorityBase< PRIO > &  other) const [inline]

Definition at line 54 of file constraint_base.h.

template<typename PRIO = uint32_t>
bool PriorityBase< PRIO >::operator== ( const PriorityBase< PRIO > &  other) const [inline]

Definition at line 64 of file constraint_base.h.

template<typename PRIO = uint32_t>
bool PriorityBase< PRIO >::operator> ( const PriorityBase< PRIO > &  other) const [inline]

Definition at line 59 of file constraint_base.h.

template<typename PRIO = uint32_t>
void PriorityBase< PRIO >::setPriority ( PRIO  prio) [inline]

Definition at line 49 of file constraint_base.h.

template<typename PRIO = uint32_t>
virtual void PriorityBase< PRIO >::update ( const JointStates joint_states,
const KDL::JntArrayVel joints_prediction,
const Matrix6Xd_t jacobian_data 
) [pure virtual]

Member Data Documentation

template<typename PRIO = uint32_t>
PRIO PriorityBase< PRIO >::priority_ [protected]

Definition at line 98 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 Jun 6 2019 21:19:26