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::ConstraintSolverFactory |
( |
CallbackDataMediator & |
data_mediator, |
|
|
KDL::ChainJntToJacSolver & |
jnt_to_jac, |
|
|
KDL::ChainFkSolverVel_recursive & |
fk_solver_vel, |
|
|
TaskStackController_t & |
task_stack_controller |
|
) |
| |
|
inline |
Ctor of ConstraintSolverFactoryBuilder.
- Parameters
-
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::~ConstraintSolverFactory |
( |
| ) |
|
|
inline |
◆ calculateJointVelocities()
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.
- Parameters
-
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. |
- Returns
- The calculated new joint velocities in (m x 1)-Matrix.
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.
◆ getSolverFactory()
Given a constraint_type create a solver_factory instance and return it. In case of an error false will be returned.
- Parameters
-
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.
◆ resetAll()
◆ constraints_
◆ damping_method_
◆ data_mediator_
◆ fk_solver_vel_
KDL::ChainFkSolverVel_recursive& ConstraintSolverFactory::fk_solver_vel_ |
|
private |
◆ jnt_to_jac_
KDL::ChainJntToJacSolver& ConstraintSolverFactory::jnt_to_jac_ |
|
private |
◆ solver_factory_
◆ task_stack_controller_
The documentation for this class was generated from the following files: