#include <wln_joint_limit_avoidance_solver.h>

Public Member Functions | |
| WLN_JointLimitAvoidanceSolver (const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller) | |
| virtual | ~WLN_JointLimitAvoidanceSolver () |
Public Member Functions inherited from WeightedLeastNormSolver | |
| virtual Eigen::MatrixXd | solve (const Vector6d_t &in_cart_velocities, const JointStates &joint_states) |
| WeightedLeastNormSolver (const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller) | |
| virtual | ~WeightedLeastNormSolver () |
Public Member Functions inherited from ConstraintSolver<> | |
| void | clearConstraints () |
| ConstraintSolver (const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller) | |
| void | setConstraints (std::set< ConstraintBase_t > &constraints) |
| void | setDamping (boost::shared_ptr< DampingBase > &damping) |
| virtual void | setJacobianData (const Matrix6Xd_t &jacobian_data) |
| virtual | ~ConstraintSolver () |
Private Member Functions | |
| virtual Eigen::MatrixXd | calculateWeighting (const JointStates &joint_states) const |
Additional Inherited Members | |
Protected Attributes inherited from ConstraintSolver<> | |
| std::set< ConstraintBase_t > | constraints_ |
| set inserts sorted (default less operator); if element has already been added it returns an iterator on it. More... | |
| boost::shared_ptr< DampingBase > | damping_ |
| References the current Jacobian (matrix data only). More... | |
| Matrix6Xd_t | jacobian_data_ |
| References the limiter parameters (up-to-date according to KinematicExtension). More... | |
| const LimiterParams & | limiter_params_ |
| References the inv. diff. kin. solver parameters. More... | |
| const TwistControllerParams & | params_ |
| Set of constraints. More... | |
| PInvBySVD | pinv_calc_ |
| The currently set damping method. More... | |
| TaskStackController_t & | task_stack_controller_ |
| An instance that helps solving the inverse of the Jacobian. More... | |
Implementation of ConstraintSolver to solve inverse kinematics with joint limit avoidance Uses solve method of the WeightedLeastNormSolver
Definition at line 26 of file wln_joint_limit_avoidance_solver.h.
|
inline |
Definition at line 29 of file wln_joint_limit_avoidance_solver.h.
|
inlinevirtual |
Definition at line 35 of file wln_joint_limit_avoidance_solver.h.
|
privatevirtual |
Helper method that calculates a weighting for the Jacobian to adapt the impact on joint velocities. Overridden from base class WLNSolver
| q | The current joint positions. |
| q_dot | The current joint velocities. |
This function calculates the weighting matrix used to penalize a joint when it is near and moving towards a limit. The last joint velocity is used to determine if it that happens or not
Reimplemented from WeightedLeastNormSolver.
Definition at line 27 of file wln_joint_limit_avoidance_solver.cpp.