$search

reem_kinematics_constraint_aware::JointPositionLimitsAvoider Class Reference

#include <ik_solver.h>

List of all members.

Public Member Functions

JointPositionLimitsAvoiderapplyJointLimitAvoidance (const Eigen::VectorXd &q)
 Scales existing joint space weights to avoid joitn position limits.
const Eigen::VectorXd & getWeights () const
Eigen::VectorXd & getWeights ()
bool isValid (const Eigen::VectorXd &q)
 JointPositionLimitsAvoider (int q_dim)
JointPositionLimitsAvoiderresetJointLimitAvoidance ()
JointPositionLimitsAvoidersetJointLimits (const Eigen::VectorXd &q_min, const Eigen::VectorXd &q_max, double activation_window)
JointPositionLimitsAvoidersetSmoothing (const double smoothing)
JointPositionLimitsAvoidersetWeights (const Eigen::VectorXd &w)

Private Attributes

Eigen::VectorXd q_activation_max_
 Joint limit avoidance activation threshold for upper limit.
Eigen::VectorXd q_activation_min_
 Joint limit avoidance activation threshold for lower limit.
Eigen::VectorXd q_activation_size_
Eigen::VectorXd q_max_
 Maximum joint position limits.
Eigen::VectorXd q_min_
 Minimum joint position limits.
double smoothing_
 Joint limit avoidance activation size.
Eigen::VectorXd w_
 Diagonal of joint-space weight matrix not taking into account joint limit avoidance.
Eigen::VectorXd w_scaled_
 Scaled version of w_ taking into account joint limit avoidance.
Eigen::VectorXd w_scaling_
 Scaling to apply to w_ to take into account joint limit avoidance.
Eigen::VectorXd w_scaling_prev_
 Previous value of w_scaling_.

Detailed Description

Keeps track of vector representing entries of the diagonal of the inverse of a joint space weight matrix. Updates weights according to the closeness of the current joint positions to their respective joint limits. This enables joint limit avoidance in the presence of redundancy.

Note:
This class makes use of the named parameter idiom for setting/resetting parameters.

Definition at line 72 of file ik_solver.h.


Constructor & Destructor Documentation

reem_kinematics_constraint_aware::JointPositionLimitsAvoider::JointPositionLimitsAvoider ( int  q_dim  )  [inline]
Parameters:
q_dim Joint space dimension

Definition at line 76 of file ik_solver.h.


Member Function Documentation

JointPositionLimitsAvoider & JointPositionLimitsAvoider::applyJointLimitAvoidance ( const Eigen::VectorXd &  q  ) 

Scales existing joint space weights to avoid joitn position limits.

Parameters:
q joint position values.

Definition at line 297 of file ik_solver.cpp.

const Eigen::VectorXd& reem_kinematics_constraint_aware::JointPositionLimitsAvoider::getWeights (  )  const [inline]

Definition at line 104 of file ik_solver.h.

Eigen::VectorXd& reem_kinematics_constraint_aware::JointPositionLimitsAvoider::getWeights (  )  [inline]

Definition at line 103 of file ik_solver.h.

bool reem_kinematics_constraint_aware::JointPositionLimitsAvoider::isValid ( const Eigen::VectorXd &  q  )  [inline]
Returns:
true if input is within the valid joint position limits.

Definition at line 126 of file ik_solver.h.

JointPositionLimitsAvoider& reem_kinematics_constraint_aware::JointPositionLimitsAvoider::resetJointLimitAvoidance (  )  [inline]

Definition at line 113 of file ik_solver.h.

JointPositionLimitsAvoider & JointPositionLimitsAvoider::setJointLimits ( const Eigen::VectorXd &  q_min,
const Eigen::VectorXd &  q_max,
double  activation_window 
)
Parameters:
q_min Minimum joint position limits.
q_max Maximum joint position limits.
activation_window Size of the joint limit avoidance activation zone. Value belongs to [0, 1]. E.g., if set to 0.1, the activation zones (one at each joint limit) will have size 0.1|q_max - q_min|.

Definition at line 281 of file ik_solver.cpp.

JointPositionLimitsAvoider& reem_kinematics_constraint_aware::JointPositionLimitsAvoider::setSmoothing ( const double  smoothing  )  [inline]

Definition at line 106 of file ik_solver.h.

JointPositionLimitsAvoider& reem_kinematics_constraint_aware::JointPositionLimitsAvoider::setWeights ( const Eigen::VectorXd &  w  )  [inline]

Definition at line 96 of file ik_solver.h.


Member Data Documentation

Joint limit avoidance activation threshold for upper limit.

Definition at line 144 of file ik_solver.h.

Joint limit avoidance activation threshold for lower limit.

Definition at line 143 of file ik_solver.h.

Definition at line 145 of file ik_solver.h.

Maximum joint position limits.

Definition at line 142 of file ik_solver.h.

Minimum joint position limits.

Definition at line 141 of file ik_solver.h.

Joint limit avoidance activation size.

Smoothing factor used when restoring joint space weights when a joint inside the avoidance interval starts moving away from it. Value belongs to [0, 1].

Definition at line 149 of file ik_solver.h.

Diagonal of joint-space weight matrix not taking into account joint limit avoidance.

Definition at line 137 of file ik_solver.h.

Scaled version of w_ taking into account joint limit avoidance.

Definition at line 138 of file ik_solver.h.

Scaling to apply to w_ to take into account joint limit avoidance.

Definition at line 139 of file ik_solver.h.

Previous value of w_scaling_.

Definition at line 140 of file ik_solver.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


reem_kinematics_constraint_aware
Author(s): Adolfo Rodriguez Tsouroukdissian, Hilario Tome.
autogenerated on Fri Mar 1 17:27:14 2013