Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef COB_TWIST_CONTROLLER_INVERSE_DIFFERENTIAL_KINEMATICS_SOLVER_H
00019 #define COB_TWIST_CONTROLLER_INVERSE_DIFFERENTIAL_KINEMATICS_SOLVER_H
00020
00021 #include <kdl/chainjnttojacsolver.hpp>
00022 #include <kdl/chainfksolvervel_recursive.hpp>
00023 #include <Eigen/Core>
00024 #include <Eigen/Geometry>
00025
00026 #include "cob_twist_controller/cob_twist_controller_data_types.h"
00027 #include "cob_twist_controller/callback_data_mediator.h"
00028 #include "cob_twist_controller/limiters/limiter.h"
00029 #include "cob_twist_controller/kinematic_extensions/kinematic_extension_builder.h"
00030 #include "cob_twist_controller/constraint_solvers/constraint_solver_factory.h"
00031 #include "cob_twist_controller/task_stack/task_stack_controller.h"
00032
00042 class InverseDifferentialKinematicsSolver
00043 {
00044 public:
00052 InverseDifferentialKinematicsSolver(const TwistControllerParams& params, const KDL::Chain& chain, CallbackDataMediator& data_mediator) :
00053 params_(params),
00054 limiter_params_(params_.limiter_params),
00055 chain_(chain),
00056 jac_(chain_.getNrOfJoints()),
00057 jnt2jac_(chain_),
00058 fk_solver_vel_(chain_),
00059 callback_data_mediator_(data_mediator),
00060 constraint_solver_factory_(data_mediator, jnt2jac_, fk_solver_vel_, task_stack_controller_)
00061 {
00062 this->kinematic_extension_.reset(KinematicExtensionBuilder::createKinematicExtension(this->params_));
00063 this->limiter_params_ = this->kinematic_extension_->adjustLimiterParams(this->limiter_params_);
00064
00065 this->limiters_.reset(new LimiterContainer(this->limiter_params_));
00066 this->limiters_->init();
00067 }
00068
00069 virtual ~InverseDifferentialKinematicsSolver()
00070 {
00071 this->limiters_.reset();
00072 this->kinematic_extension_.reset();
00073 };
00074
00076 virtual int CartToJnt(const JointStates& joint_states,
00077 const KDL::Twist& v_in,
00078 KDL::JntArray& qdot_out);
00079
00080 void resetAll(TwistControllerParams params);
00081
00082 private:
00083 const KDL::Chain chain_;
00084 KDL::Jacobian jac_;
00085 KDL::ChainFkSolverVel_recursive fk_solver_vel_;
00086 KDL::ChainJntToJacSolver jnt2jac_;
00087 TwistControllerParams params_;
00088 LimiterParams limiter_params_;
00089 CallbackDataMediator& callback_data_mediator_;
00090 boost::shared_ptr<LimiterContainer> limiters_;
00091 boost::shared_ptr<KinematicExtensionBase> kinematic_extension_;
00092 ConstraintSolverFactory constraint_solver_factory_;
00093
00094 TaskStackController_t task_stack_controller_;
00095 };
00096
00097 #endif // COB_TWIST_CONTROLLER_INVERSE_DIFFERENTIAL_KINEMATICS_SOLVER_H