Base class for solvers, defining interface methods. More...
#include <constraint_solver_base.h>
| Public Member Functions | |
| 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 Eigen::MatrixXd | solve (const Vector6d_t &in_cart_velocities, const JointStates &joint_states)=0 | 
| virtual | ~ConstraintSolver () | 
| Protected Attributes | |
| std::set< ConstraintBase_t > | constraints_ | 
| set inserts sorted (default less operator); if element has already been added it returns an iterator on it. | |
| boost::shared_ptr< DampingBase > | damping_ | 
| References the current Jacobian (matrix data only). | |
| Matrix6Xd_t | jacobian_data_ | 
| References the limiter parameters (up-to-date according to KinematicExtension). | |
| const LimiterParams & | limiter_params_ | 
| References the inv. diff. kin. solver parameters. | |
| const TwistControllerParams & | params_ | 
| Set of constraints. | |
| PINV | pinv_calc_ | 
| The currently set damping method. | |
| TaskStackController_t & | task_stack_controller_ | 
| An instance that helps solving the inverse of the Jacobian. | |
Base class for solvers, defining interface methods.
Definition at line 33 of file constraint_solver_base.h.
| virtual ConstraintSolver< PINV >::~ConstraintSolver | ( | ) |  [inline, virtual] | 
Definition at line 80 of file constraint_solver_base.h.
| ConstraintSolver< PINV >::ConstraintSolver | ( | const TwistControllerParams & | params, | 
| const LimiterParams & | limiter_params, | ||
| TaskStackController_t & | task_stack_controller | ||
| ) |  [inline] | 
Definition at line 85 of file constraint_solver_base.h.
| void ConstraintSolver< PINV >::clearConstraints | ( | ) |  [inline] | 
Calls destructor on all objects and clears the set
Definition at line 67 of file constraint_solver_base.h.
| void ConstraintSolver< PINV >::setConstraints | ( | std::set< ConstraintBase_t > & | constraints | ) |  [inline] | 
Set all created constraints in a (priorized) set.
| constraints,: | All constraints ordered according to priority. | 
Definition at line 58 of file constraint_solver_base.h.
| void ConstraintSolver< PINV >::setDamping | ( | boost::shared_ptr< DampingBase > & | damping | ) |  [inline] | 
Inline method to set the damping
| damping | The new damping | 
Definition at line 49 of file constraint_solver_base.h.
| virtual void ConstraintSolver< PINV >::setJacobianData | ( | const Matrix6Xd_t & | jacobian_data | ) |  [inline, virtual] | 
Method to initialize the solver if necessary
Definition at line 75 of file constraint_solver_base.h.
| virtual Eigen::MatrixXd ConstraintSolver< PINV >::solve | ( | const Vector6d_t & | in_cart_velocities, | 
| const JointStates & | joint_states | ||
| ) |  [pure virtual] | 
The interface method to solve the inverse kinematics problem. Has to be implemented in inherited classes.
| in_cart_velocities | The input velocities vector (in cartesian space). | 
| joint_states | The joint states with history. | 
Implemented in StackOfTasksSolver, TaskPrioritySolver, GradientProjectionMethodSolver, UnifiedJointLimitSingularitySolver, WeightedLeastNormSolver, and UnconstraintSolver.
| std::set<ConstraintBase_t> ConstraintSolver< PINV >::constraints_  [protected] | 
set inserts sorted (default less operator); if element has already been added it returns an iterator on it.
Definition at line 95 of file constraint_solver_base.h.
| boost::shared_ptr<DampingBase> ConstraintSolver< PINV >::damping_  [protected] | 
References the current Jacobian (matrix data only).
Definition at line 99 of file constraint_solver_base.h.
| Matrix6Xd_t ConstraintSolver< PINV >::jacobian_data_  [protected] | 
References the limiter parameters (up-to-date according to KinematicExtension).
Definition at line 98 of file constraint_solver_base.h.
| const LimiterParams& ConstraintSolver< PINV >::limiter_params_  [protected] | 
References the inv. diff. kin. solver parameters.
Definition at line 97 of file constraint_solver_base.h.
| const TwistControllerParams& ConstraintSolver< PINV >::params_  [protected] | 
Set of constraints.
Definition at line 96 of file constraint_solver_base.h.
| PINV ConstraintSolver< PINV >::pinv_calc_  [protected] | 
The currently set damping method.
Definition at line 100 of file constraint_solver_base.h.
| TaskStackController_t& ConstraintSolver< PINV >::task_stack_controller_  [protected] | 
An instance that helps solving the inverse of the Jacobian.
Definition at line 101 of file constraint_solver_base.h.