Implementation of ConstraintSolver to solve inverse kinematics by using a weighted least norm. More...
#include <weighted_least_norm_solver.h>
Public Member Functions | |
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 () |
Private Member Functions | |
virtual Eigen::MatrixXd | calculateWeighting (const JointStates &joint_states) const |
Implementation of ConstraintSolver to solve inverse kinematics by using a weighted least norm.
Definition at line 25 of file weighted_least_norm_solver.h.
WeightedLeastNormSolver::WeightedLeastNormSolver | ( | const TwistControllerParams & | params, |
const LimiterParams & | limiter_params, | ||
TaskStackController_t & | task_stack_controller | ||
) | [inline] |
Definition at line 28 of file weighted_least_norm_solver.h.
virtual WeightedLeastNormSolver::~WeightedLeastNormSolver | ( | ) | [inline, virtual] |
Definition at line 34 of file weighted_least_norm_solver.h.
Eigen::MatrixXd WeightedLeastNormSolver::calculateWeighting | ( | const JointStates & | joint_states | ) | const [private, virtual] |
Virtual helper method that calculates a weighting for the Jacobian to adapt joint velocity calculation for given constraints.
q | The current joint positions. |
q_dot | The current joint velocities. |
This function returns the identity as weighting matrix for base functionality.
Reimplemented in WLN_JointLimitAvoidanceSolver.
Definition at line 45 of file weighted_least_norm_solver.cpp.
Eigen::MatrixXd WeightedLeastNormSolver::solve | ( | const Vector6d_t & | in_cart_velocities, |
const JointStates & | joint_states | ||
) | [virtual] |
Specific implementation of solve-method to solve IK problem with joint limit avoidance. See base class ConstraintSolver for more details on params and returns.
Specific implementation of the solve method using a weighted least norm. This is done by calculation of a weighting which is dependent on inherited classes for the Jacobian. Uses the base implementation of calculatePinvJacobianBySVD to calculate the pseudo-inverse (weighted) Jacobian.
Implements ConstraintSolver<>.
Definition at line 25 of file weighted_least_norm_solver.cpp.