Public Member Functions | Private Member Functions
WLN_JointLimitAvoidanceSolver Class Reference

#include <wln_joint_limit_avoidance_solver.h>

Inheritance diagram for WLN_JointLimitAvoidanceSolver:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 WLN_JointLimitAvoidanceSolver (const TwistControllerParams &params, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller)
virtual ~WLN_JointLimitAvoidanceSolver ()

Private Member Functions

virtual Eigen::MatrixXd calculateWeighting (const JointStates &joint_states) const

Detailed Description

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.


Constructor & Destructor Documentation

WLN_JointLimitAvoidanceSolver::WLN_JointLimitAvoidanceSolver ( const TwistControllerParams params,
const LimiterParams limiter_params,
TaskStackController_t task_stack_controller 
) [inline]

Definition at line 29 of file wln_joint_limit_avoidance_solver.h.

Definition at line 35 of file wln_joint_limit_avoidance_solver.h.


Member Function Documentation

Eigen::MatrixXd WLN_JointLimitAvoidanceSolver::calculateWeighting ( const JointStates joint_states) const [private, virtual]

Helper method that calculates a weighting for the Jacobian to adapt the impact on joint velocities. Overridden from base class WLNSolver

Parameters:
qThe current joint positions.
q_dotThe current joint velocities.
Returns:
Diagonal weighting matrix that adapts the Jacobian.

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.


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