Public Member Functions | Private Member Functions | Private Attributes
JointLimitAvoidanceIneq< T_PARAMS, PRIO > Class Template Reference

Class providing methods that realize a JointLimitAvoidance constraint based on inequalities. More...

#include <constraint.h>

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

List of all members.

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.
virtual Eigen::VectorXd getTaskDerivatives () const
virtual std::string getTaskId () const
virtual Eigen::MatrixXd getTaskJacobian () const
 JointLimitAvoidanceIneq (PRIO prio, T_PARAMS constraint_params, CallbackDataMediator &cbdm)
virtual ~JointLimitAvoidanceIneq ()

Private Member Functions

void calcDerivativeValue ()
 Simple first order differential equation for exponential increase (move away from limit!)
void calcPartialValues ()
 Calculates values of the gradient of the cost function.
void calcValue ()
 Calculate values of the JLA cost function.

Private Attributes

double abs_delta_max_
double abs_delta_min_
double rel_max_
double rel_min_

Detailed Description

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

Class providing methods that realize a JointLimitAvoidance constraint based on inequalities.

Definition at line 171 of file constraint.h.


Constructor & Destructor Documentation

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

Definition at line 174 of file constraint.h.

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

Definition at line 184 of file constraint.h.


Member Function Documentation

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceIneq< T_PARAMS, PRIO >::calcDerivativeValue ( ) [private]

Simple first order differential equation for exponential increase (move away from limit!)

Definition at line 460 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceIneq< T_PARAMS, PRIO >::calcPartialValues ( ) [private]

Calculates values of the gradient of the cost function.

Definition at line 467 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceIneq< T_PARAMS, PRIO >::calculate ( ) [virtual]

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 325 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
void JointLimitAvoidanceIneq< T_PARAMS, PRIO >::calcValue ( ) [private]

Calculate values of the JLA cost function.

Definition at line 445 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
double JointLimitAvoidanceIneq< T_PARAMS, PRIO >::getActivationGain ( ) const [virtual]

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 378 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
double JointLimitAvoidanceIneq< 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 419 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
Eigen::VectorXd JointLimitAvoidanceIneq< T_PARAMS, PRIO >::getTaskDerivatives ( ) const [virtual]

Reimplemented from ConstraintBase< T_PARAMS, PRIO >.

Definition at line 319 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
std::string JointLimitAvoidanceIneq< T_PARAMS, PRIO >::getTaskId ( ) const [virtual]

Implements ConstraintBase< T_PARAMS, PRIO >.

Definition at line 302 of file constraint_jla_impl.h.

template<typename T_PARAMS , typename PRIO >
Eigen::MatrixXd JointLimitAvoidanceIneq< T_PARAMS, PRIO >::getTaskJacobian ( ) const [virtual]

Reimplemented from ConstraintBase< T_PARAMS, PRIO >.

Definition at line 313 of file constraint_jla_impl.h.


Member Data Documentation

template<typename T_PARAMS , typename PRIO = uint32_t>
double JointLimitAvoidanceIneq< T_PARAMS, PRIO >::abs_delta_max_ [private]

Definition at line 201 of file constraint.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double JointLimitAvoidanceIneq< T_PARAMS, PRIO >::abs_delta_min_ [private]

Definition at line 202 of file constraint.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double JointLimitAvoidanceIneq< T_PARAMS, PRIO >::rel_max_ [private]

Definition at line 203 of file constraint.h.

template<typename T_PARAMS , typename PRIO = uint32_t>
double JointLimitAvoidanceIneq< T_PARAMS, PRIO >::rel_min_ [private]

Definition at line 204 of file constraint.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 Jun 6 2019 21:19:26