#include <unconstraint_solver.h>
Public Member Functions | |
virtual Eigen::MatrixXd | solve (const Vector6d_t &in_cart_velocities, const JointStates &joint_states) |
UnconstraintSolver (const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller) | |
virtual | ~UnconstraintSolver () |
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 () |
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... | |
Definition at line 24 of file unconstraint_solver.h.
|
inline |
Definition at line 27 of file unconstraint_solver.h.
|
inlinevirtual |
Definition at line 33 of file unconstraint_solver.h.
|
virtual |
Specific implementation of solve-method to solve IK problem without any constraints. See base class ConstraintSolver for more details on params and returns.
Implementation of a default solve-method for the inverse kinematics problem. It calculates the pseudo-inverse of the Jacobian via the base implementation of calculatePinvJacobianBySVD. With the pseudo-inverse the joint velocity vector is calculated.
Implements ConstraintSolver<>.
Definition at line 27 of file unconstraint_solver.cpp.