Class providing methods that realize a JointLimitAvoidance constraint based on inequalities. More...
#include <constraint.h>

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 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 () |
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 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 () |
| Simple first order differential equation for exponential increase (move away from limit!) More... | |
| void | calcPartialValues () |
| Calculates values of the gradient of the cost function. More... | |
| void | calcValue () |
| Calculate values of the JLA cost function. More... | |
Private Attributes | |
| double | abs_delta_max_ |
| double | abs_delta_min_ |
| double | rel_max_ |
| double | rel_min_ |
Additional Inherited Members | |
Protected Member Functions inherited from ConstraintBase< T_PARAMS, PRIO > | |
| virtual double | getCriticalValue () const |
Protected Attributes inherited from ConstraintBase< T_PARAMS, PRIO > | |
| CallbackDataMediator & | callback_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 |
Class providing methods that realize a JointLimitAvoidance constraint based on inequalities.
Definition at line 171 of file constraint.h.
|
inline |
Definition at line 174 of file constraint.h.
|
inlinevirtual |
Definition at line 184 of file constraint.h.
|
private |
Simple first order differential equation for exponential increase (move away from limit!)
Definition at line 460 of file constraint_jla_impl.h.
|
private |
Calculates values of the gradient of the cost function.
Definition at line 467 of file constraint_jla_impl.h.
|
virtual |
Implements ConstraintBase< T_PARAMS, PRIO >.
Definition at line 325 of file constraint_jla_impl.h.
|
private |
Calculate values of the JLA cost function.
Definition at line 445 of file constraint_jla_impl.h.
|
virtual |
Implements ConstraintBase< T_PARAMS, PRIO >.
Definition at line 378 of file constraint_jla_impl.h.
|
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.
|
virtual |
Reimplemented from ConstraintBase< T_PARAMS, PRIO >.
Definition at line 319 of file constraint_jla_impl.h.
|
virtual |
Implements ConstraintBase< T_PARAMS, PRIO >.
Definition at line 302 of file constraint_jla_impl.h.
|
virtual |
Reimplemented from ConstraintBase< T_PARAMS, PRIO >.
Definition at line 313 of file constraint_jla_impl.h.
|
private |
Definition at line 201 of file constraint.h.
|
private |
Definition at line 202 of file constraint.h.
|
private |
Definition at line 203 of file constraint.h.
|
private |
Definition at line 204 of file constraint.h.