Go to the documentation of this file.
18 #ifndef COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_CONSTRAINT_SOLVER_FACTORY_H
19 #define COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_CONSTRAINT_SOLVER_FACTORY_H
24 #include <kdl/jntarray.hpp>
25 #include <kdl/chainjnttojacsolver.hpp>
26 #include <kdl/chainfksolvervel_recursive.hpp>
27 #include <boost/shared_ptr.hpp>
43 KDL::ChainJntToJacSolver& jnt_to_jac,
44 KDL::ChainFkSolverVel_recursive& fk_solver_vel,
73 Eigen::MatrixXd& out_jnt_velocities);
99 #endif // COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_CONSTRAINT_SOLVER_FACTORY_H
KDL::ChainFkSolverVel_recursive & fk_solver_vel_
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 ¶ms, const LimiterParams &limiter_params)
~ConstraintSolverFactory()
CallbackDataMediator & data_mediator_
boost::shared_ptr< ISolverFactory > solver_factory_
std::set< ConstraintBase_t > constraints_
Static class providing a single method for creation of damping method, solver and starting the solvin...
int8_t calculateJointVelocities(Matrix6Xd_t &jacobian_data, const Vector6d_t &in_cart_velocities, const JointStates &joint_states, Eigen::MatrixXd &out_jnt_velocities)
Eigen::Matrix< double, 6, 1 > Vector6d_t
boost::shared_ptr< DampingBase > damping_method_
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6Xd_t
TaskStackController_t & task_stack_controller_
KDL::ChainJntToJacSolver & jnt_to_jac_
static bool getSolverFactory(const TwistControllerParams ¶ms, const LimiterParams &limiter_params, boost::shared_ptr< ISolverFactory > &solver_factory, TaskStackController_t &task_stack_controller)
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43