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. 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... | |
PINV | pinv_calc_ |
The currently set damping method. More... | |
TaskStackController_t & | task_stack_controller_ |
An instance that helps solving the inverse of the Jacobian. More... | |
Base class for solvers, defining interface methods.
Definition at line 33 of file constraint_solver_base.h.
|
inlinevirtual |
Definition at line 80 of file constraint_solver_base.h.
|
inline |
Definition at line 85 of file constraint_solver_base.h.
|
inline |
Calls destructor on all objects and clears the set
Definition at line 67 of file constraint_solver_base.h.
|
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.
|
inline |
Inline method to set the damping
damping | The new damping |
Definition at line 49 of file constraint_solver_base.h.
|
inlinevirtual |
Method to initialize the solver if necessary
Definition at line 75 of file constraint_solver_base.h.
|
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.
|
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.
|
protected |
References the current Jacobian (matrix data only).
Definition at line 99 of file constraint_solver_base.h.
|
protected |
References the limiter parameters (up-to-date according to KinematicExtension).
Definition at line 98 of file constraint_solver_base.h.
|
protected |
References the inv. diff. kin. solver parameters.
Definition at line 97 of file constraint_solver_base.h.
|
protected |
Set of constraints.
Definition at line 96 of file constraint_solver_base.h.
|
protected |
The currently set damping method.
Definition at line 100 of file constraint_solver_base.h.
|
protected |
An instance that helps solving the inverse of the Jacobian.
Definition at line 101 of file constraint_solver_base.h.