Public Member Functions | Static Public Member Functions | Private Attributes
ConstraintSolverFactory Class Reference

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>

List of all members.

Public Member Functions

int8_t calculateJointVelocities (Matrix6Xd_t &jacobian_data, const Vector6d_t &in_cart_velocities, const JointStates &joint_states, Eigen::MatrixXd &out_jnt_velocities)
 ConstraintSolverFactory (CallbackDataMediator &data_mediator, KDL::ChainJntToJacSolver &jnt_to_jac, KDL::ChainFkSolverVel_recursive &fk_solver_vel, TaskStackController_t &task_stack_controller)
int8_t resetAll (const TwistControllerParams &params, const LimiterParams &limiter_params)
 ~ConstraintSolverFactory ()

Static Public Member Functions

static bool getSolverFactory (const TwistControllerParams &params, const LimiterParams &limiter_params, boost::shared_ptr< ISolverFactory > &solver_factory, TaskStackController_t &task_stack_controller)

Private Attributes

std::set< ConstraintBase_tconstraints_
boost::shared_ptr< DampingBasedamping_method_
CallbackDataMediatordata_mediator_
KDL::ChainFkSolverVel_recursivefk_solver_vel_
KDL::ChainJntToJacSolverjnt_to_jac_
boost::shared_ptr< ISolverFactorysolver_factory_
TaskStackController_ttask_stack_controller_

Detailed Description

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.


Constructor & Destructor Documentation

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.

Definition at line 55 of file constraint_solver_factory.h.


Member Function Documentation

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:
paramsReferences the inv. diff. kin. solver parameters.
jacobian_dataReferences the current Jacobian (matrix data only).
in_cart_velocitiesThe input velocities vector (in cartesian space).
joint_statesThe joint states and history.
out_jnt_velocitiesThe 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.

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.

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.

int8_t ConstraintSolverFactory::resetAll ( const TwistControllerParams params,
const LimiterParams limiter_params 
)

Definition at line 115 of file constraint_solver_factory.cpp.


Member Data Documentation

Definition at line 95 of file constraint_solver_factory.h.

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.

Definition at line 93 of file constraint_solver_factory.h.

Definition at line 96 of file constraint_solver_factory.h.


The documentation for this class was generated from the following files:


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26