Class providing methods that realize a CollisionAvoidance constraint. More...
#include <constraint.h>
Public Member Functions | |
virtual void | calculate () |
CollisionAvoidance (PRIO prio, T_PARAMS constraint_params, CallbackDataMediator &cbdm, KDL::ChainJntToJacSolver &jnt_to_jac, KDL::ChainFkSolverVel_recursive &fk_solver_vel) | |
virtual double | getActivationGain () const |
double | getActivationGain (double current_cost_func_value) 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... | |
double | getSelfMotionMagnitude (double current_cost_func_value) const |
Returns a value for magnitude. More... | |
virtual Eigen::VectorXd | getTaskDerivatives () const |
virtual std::string | getTaskId () const |
virtual Eigen::MatrixXd | getTaskJacobian () const |
virtual | ~CollisionAvoidance () |
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 () |
void | calcPartialValues () |
void | calcPredictionValue () |
void | calcValue () |
double | getActivationThresholdWithBuffer () const |
virtual double | getCriticalValue () const |
Private Attributes | |
Eigen::VectorXd | derivative_values_ |
KDL::ChainFkSolverVel_recursive & | fk_solver_vel_ |
KDL::ChainJntToJacSolver & | jnt_to_jac_ |
Eigen::MatrixXd | task_jacobian_ |
Eigen::VectorXd | values_ |
Additional Inherited Members | |
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 CollisionAvoidance constraint.
Definition at line 52 of file constraint.h.
|
inline |
Definition at line 55 of file constraint.h.
|
inlinevirtual |
Definition at line 65 of file constraint.h.
|
private |
Definition at line 220 of file constraint_ca_impl.h.
|
private |
Calculate the partial values for each obstacle with the current link. For GPM the partial values are summed. For task constraint the task Jacobian is created: Each row is the partial value vector of one collision pair. ATTENTION: The magnitude and activation gain are considered only for GPM here.
Definition at line 233 of file constraint_ca_impl.h.
|
private |
Definition at line 344 of file constraint_ca_impl.h.
|
virtual |
Implements ConstraintBase< T_PARAMS, PRIO >.
Definition at line 79 of file constraint_ca_impl.h.
|
private |
Definition at line 191 of file constraint_ca_impl.h.
|
virtual |
Implements ConstraintBase< T_PARAMS, PRIO >.
Definition at line 137 of file constraint_ca_impl.h.
double CollisionAvoidance< T_PARAMS, PRIO >::getActivationGain | ( | double | current_cost_func_value | ) | const |
Definition at line 113 of file constraint_ca_impl.h.
|
private |
|
privatevirtual |
Reimplemented from ConstraintBase< T_PARAMS, PRIO >.
Definition at line 174 of file constraint_ca_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 168 of file constraint_ca_impl.h.
double CollisionAvoidance< T_PARAMS, PRIO >::getSelfMotionMagnitude | ( | double | current_cost_func_value | ) | const |
Returns a value for magnitude.
Definition at line 144 of file constraint_ca_impl.h.
|
virtual |
1x1 Vector returning the task derivative of a CA constraint. One row task Jacobian <-> One dim derivative.
Reimplemented from ConstraintBase< T_PARAMS, PRIO >.
Definition at line 73 of file constraint_ca_impl.h.
|
virtual |
Implements ConstraintBase< T_PARAMS, PRIO >.
Definition at line 43 of file constraint_ca_impl.h.
|
virtual |
Critical Point Jacobian: Each critical point is represented by one CA constraint. So the partial values represent a one row task Jacobian.
Reimplemented from ConstraintBase< T_PARAMS, PRIO >.
Definition at line 62 of file constraint_ca_impl.h.
|
private |
Definition at line 94 of file constraint.h.
|
private |
Definition at line 91 of file constraint.h.
|
private |
Definition at line 90 of file constraint.h.
|
private |
Definition at line 95 of file constraint.h.
|
private |
Definition at line 93 of file constraint.h.