inverse_differential_kinematics_solver.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_TWIST_CONTROLLER_INVERSE_DIFFERENTIAL_KINEMATICS_SOLVER_H
19 #define COB_TWIST_CONTROLLER_INVERSE_DIFFERENTIAL_KINEMATICS_SOLVER_H
20 
21 #include <kdl/chainjnttojacsolver.hpp>
22 #include <kdl/chainfksolvervel_recursive.hpp>
23 #include <Eigen/Core>
24 #include <Eigen/Geometry>
25 
32 
43 {
44 public:
52  InverseDifferentialKinematicsSolver(const TwistControllerParams& params, const KDL::Chain& chain, CallbackDataMediator& data_mediator) :
53  params_(params),
54  limiter_params_(params_.limiter_params),
55  chain_(chain),
56  jac_(chain_.getNrOfJoints()),
59  callback_data_mediator_(data_mediator),
61  {
63  this->limiter_params_ = this->kinematic_extension_->adjustLimiterParams(this->limiter_params_);
64 
65  this->limiters_.reset(new LimiterContainer(this->limiter_params_));
66  this->limiters_->init();
67  }
68 
70  {
71  this->limiters_.reset();
72  this->kinematic_extension_.reset();
73  };
74 
76  virtual int CartToJnt(const JointStates& joint_states,
77  const KDL::Twist& v_in,
78  KDL::JntArray& qdot_out);
79 
80  bool resetAll(TwistControllerParams params);
81 
82 private:
83  const KDL::Chain chain_;
84  KDL::Jacobian jac_;
85  KDL::ChainFkSolverVel_recursive fk_solver_vel_;
86  KDL::ChainJntToJacSolver jnt2jac_;
93 
95 };
96 
97 #endif // COB_TWIST_CONTROLLER_INVERSE_DIFFERENTIAL_KINEMATICS_SOLVER_H
InverseDifferentialKinematicsSolver::~InverseDifferentialKinematicsSolver
virtual ~InverseDifferentialKinematicsSolver()
Definition: inverse_differential_kinematics_solver.h:69
InverseDifferentialKinematicsSolver::callback_data_mediator_
CallbackDataMediator & callback_data_mediator_
Definition: inverse_differential_kinematics_solver.h:89
InverseDifferentialKinematicsSolver
Definition: inverse_differential_kinematics_solver.h:42
boost::shared_ptr< LimiterContainer >
InverseDifferentialKinematicsSolver::constraint_solver_factory_
ConstraintSolverFactory constraint_solver_factory_
Definition: inverse_differential_kinematics_solver.h:92
InverseDifferentialKinematicsSolver::task_stack_controller_
TaskStackController_t task_stack_controller_
Definition: inverse_differential_kinematics_solver.h:94
InverseDifferentialKinematicsSolver::jac_
KDL::Jacobian jac_
Definition: inverse_differential_kinematics_solver.h:84
InverseDifferentialKinematicsSolver::jnt2jac_
KDL::ChainJntToJacSolver jnt2jac_
Definition: inverse_differential_kinematics_solver.h:86
limiter.h
InverseDifferentialKinematicsSolver::CartToJnt
virtual int CartToJnt(const JointStates &joint_states, const KDL::Twist &v_in, KDL::JntArray &qdot_out)
Definition: inverse_differential_kinematics_solver.cpp:27
InverseDifferentialKinematicsSolver::limiter_params_
LimiterParams limiter_params_
Definition: inverse_differential_kinematics_solver.h:88
CallbackDataMediator
Represents a data pool for distribution of collected data from ROS callback.
Definition: callback_data_mediator.h:30
ConstraintSolverFactory
Static class providing a single method for creation of damping method, solver and starting the solvin...
Definition: constraint_solver_factory.h:34
InverseDifferentialKinematicsSolver::kinematic_extension_
boost::shared_ptr< KinematicExtensionBase > kinematic_extension_
Definition: inverse_differential_kinematics_solver.h:91
task_stack_controller.h
KinematicExtensionBuilder::createKinematicExtension
static KinematicExtensionBase * createKinematicExtension(const TwistControllerParams &params)
Definition: kinematic_extension_builder.cpp:26
InverseDifferentialKinematicsSolver::resetAll
bool resetAll(TwistControllerParams params)
Definition: inverse_differential_kinematics_solver.cpp:88
InverseDifferentialKinematicsSolver::chain_
const KDL::Chain chain_
Definition: inverse_differential_kinematics_solver.h:83
LimiterParams
Definition: cob_twist_controller_data_types.h:162
LimiterContainer
Container for limiters, implementing interface methods.
Definition: limiter.h:29
TaskStackController< uint32_t >
InverseDifferentialKinematicsSolver::limiters_
boost::shared_ptr< LimiterContainer > limiters_
Definition: inverse_differential_kinematics_solver.h:90
TwistControllerParams
Definition: cob_twist_controller_data_types.h:209
JointStates
Definition: cob_twist_controller_data_types.h:112
kinematic_extension_builder.h
InverseDifferentialKinematicsSolver::params_
TwistControllerParams params_
Definition: inverse_differential_kinematics_solver.h:87
InverseDifferentialKinematicsSolver::InverseDifferentialKinematicsSolver
InverseDifferentialKinematicsSolver(const TwistControllerParams &params, const KDL::Chain &chain, CallbackDataMediator &data_mediator)
Definition: inverse_differential_kinematics_solver.h:52
InverseDifferentialKinematicsSolver::fk_solver_vel_
KDL::ChainFkSolverVel_recursive fk_solver_vel_
Definition: inverse_differential_kinematics_solver.h:85
cob_twist_controller_data_types.h
constraint_solver_factory.h
callback_data_mediator.h


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43