Static class providing a single method for creation of damping method, solver and starting the solving of the IK problem. More...
#include <constraint_solver_factory.h>
Static class providing a single method for creation of damping method, solver and starting the solving of the IK problem.
Definition at line 34 of file constraint_solver_factory.h.
ConstraintSolverFactory::ConstraintSolverFactory | ( | CallbackDataMediator & | data_mediator, |
KDL::ChainJntToJacSolver & | jnt_to_jac, | ||
KDL::ChainFkSolverVel_recursive & | fk_solver_vel, | ||
TaskStackController_t & | task_stack_controller | ||
) | [inline] |
Ctor of ConstraintSolverFactoryBuilder.
data_mediator,: | Reference to an callback data mediator. |
jnt_to_jac,: | Reference to an joint to Jacobian solver. |
Definition at line 42 of file constraint_solver_factory.h.
ConstraintSolverFactory::~ConstraintSolverFactory | ( | ) | [inline] |
Definition at line 55 of file constraint_solver_factory.h.
int8_t ConstraintSolverFactory::calculateJointVelocities | ( | Matrix6Xd_t & | jacobian_data, |
const Vector6d_t & | in_cart_velocities, | ||
const JointStates & | joint_states, | ||
Eigen::MatrixXd & | out_jnt_velocities | ||
) |
Calculation of new joint velocities according to current joint positions and cartesian velocities.
params | References the inv. diff. kin. solver parameters. |
jacobian_data | References the current Jacobian (matrix data only). |
in_cart_velocities | The input velocities vector (in cartesian space). |
joint_states | The joint states and history. |
out_jnt_velocities | The calculated joint velocities as output reference. |
Out of the parameters generates a damping method (e.g. constant or manipulability) and calculates the damping factor. Dependent on JLA active flag a JointLimitAvoidanceSolver or a UnconstraintSolver is generated to solve the IK problem. The objects are generated for each solve-request. After calculation the objects are deleted.
Definition at line 39 of file constraint_solver_factory.cpp.
bool ConstraintSolverFactory::getSolverFactory | ( | const TwistControllerParams & | params, |
const LimiterParams & | limiter_params, | ||
boost::shared_ptr< ISolverFactory > & | solver_factory, | ||
TaskStackController_t & | task_stack_controller | ||
) | [static] |
Given a constraint_type create a solver_factory instance and return it. In case of an error false will be returned.
constraint_type,: | Enum value of the constraint. |
solver_factory,: | Reference of a shared pointer to be filled. |
Given a proper constraint_type a corresponding SolverFactory is generated and returned.
Definition at line 72 of file constraint_solver_factory.cpp.
int8_t ConstraintSolverFactory::resetAll | ( | const TwistControllerParams & | params, |
const LimiterParams & | limiter_params | ||
) |
Definition at line 115 of file constraint_solver_factory.cpp.
Definition at line 95 of file constraint_solver_factory.h.
boost::shared_ptr<DampingBase> ConstraintSolverFactory::damping_method_ [private] |
Definition at line 94 of file constraint_solver_factory.h.
Definition at line 89 of file constraint_solver_factory.h.
Definition at line 91 of file constraint_solver_factory.h.
Definition at line 90 of file constraint_solver_factory.h.
boost::shared_ptr<ISolverFactory> ConstraintSolverFactory::solver_factory_ [private] |
Definition at line 93 of file constraint_solver_factory.h.
Definition at line 96 of file constraint_solver_factory.h.