Public Member Functions | Private Member Functions | List of all members
JointLimitAvoidanceMid< T_PARAMS, PRIO > Class Template Reference

Class providing methods that realize a JointLimitAvoidanceMid constraint. More...

#include <constraint.h>

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

Public Member Functions

virtual void calculate ()
 
virtual double getActivationGain () const
 
virtual double getSelfMotionMagnitude (const Eigen::MatrixXd &particular_solution, const Eigen::MatrixXd &homogeneous_solution) const
 Returns a value for k_H to weight the partial values for e.g. GPM. More...
 
virtual std::string getTaskId () const
 
 JointLimitAvoidanceMid (PRIO prio, T_PARAMS constraint_params, CallbackDataMediator &cbdm)
 
virtual ~JointLimitAvoidanceMid ()
 
- Public Member Functions inherited from ConstraintBase< T_PARAMS, PRIO >
 ConstraintBase (PRIO prio, T_PARAMS params, CallbackDataMediator &cbdm)
 
virtual Task_t createTask ()
 
virtual double getDerivativeValue () const
 
virtual Eigen::VectorXd getPartialValues () const
 
virtual double getPredictionValue () const
 
virtual ConstraintState getState () const
 
virtual Eigen::VectorXd getTaskDerivatives () const
 
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 ()
 

Private Member Functions

void calcDerivativeValue ()
 Calculate derivative of values. More...
 
void calcPartialValues ()
 Calculates values of the gradient of the cost function. More...
 
void calcValue ()
 Calculate values of the JLA cost function. More...
 

Additional Inherited Members

- Protected Member Functions inherited from ConstraintBase< T_PARAMS, PRIO >
virtual double getCriticalValue () const
 
- Protected Attributes inherited from ConstraintBase< T_PARAMS, PRIO >
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 inherited from ConstraintBase< T_PARAMS, PRIO >
static uint32_t instance_ctr_ = 0
 

Detailed Description

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

Class providing methods that realize a JointLimitAvoidanceMid constraint.

Definition at line 142 of file constraint.h.

Constructor & Destructor Documentation

template<typename T_PARAMS , typename PRIO = uint32_t>
JointLimitAvoidanceMid< T_PARAMS, PRIO >::JointLimitAvoidanceMid ( PRIO  prio,
T_PARAMS  constraint_params,
CallbackDataMediator cbdm 
)
inline

Definition at line 145 of file constraint.h.

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

Definition at line 151 of file constraint.h.

Member Function Documentation

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceMid< T_PARAMS, PRIO >::calcDerivativeValue ( )
private

Calculate derivative of values.

Definition at line 251 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceMid< T_PARAMS, PRIO >::calcPartialValues ( )
private

Calculates values of the gradient of the cost function.

Definition at line 269 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceMid< T_PARAMS, PRIO >::calculate ( )
virtual

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 209 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceMid< T_PARAMS, PRIO >::calcValue ( )
private

Calculate values of the JLA cost function.

Definition at line 231 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
double JointLimitAvoidanceMid< T_PARAMS, PRIO >::getActivationGain ( ) const
virtual

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 217 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
double JointLimitAvoidanceMid< T_PARAMS, PRIO >::getSelfMotionMagnitude ( const Eigen::MatrixXd &  particular_solution,
const Eigen::MatrixXd &  homogeneous_solution 
) const
virtual

Returns a value for k_H to weight the partial values for e.g. GPM.

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 224 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
std::string JointLimitAvoidanceMid< T_PARAMS, PRIO >::getTaskId ( ) const
virtual

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 198 of file constraint_jla_impl.h.


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


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