inverse_differential_kinematics_solver.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #include <ros/ros.h>
00019 #include <eigen_conversions/eigen_kdl.h>
00020 #include <kdl/chainfksolvervel_recursive.hpp>
00021 
00022 #include "cob_twist_controller/inverse_differential_kinematics_solver.h"
00023 
00027 int InverseDifferentialKinematicsSolver::CartToJnt(const JointStates& joint_states,
00028                                                    const KDL::Twist& v_in,
00029                                                    KDL::JntArray& qdot_out)
00030 {
00031     // ROS_INFO_STREAM("joint_states.current_q_: " << joint_states.current_q_.rows());
00032     int8_t retStat = -1;
00033 
00035     KDL::Jacobian jac_chain(chain_.getNrOfJoints());
00036     jnt2jac_.JntToJac(joint_states.current_q_, jac_chain);
00037     // ROS_INFO_STREAM("jac_chain.rows: " << jac_chain.rows() << ", jac_chain.columns: " << jac_chain.columns());
00038 
00039     JointStates joint_states_full = this->kinematic_extension_->adjustJointStates(joint_states);
00040     // ROS_INFO_STREAM("joint_states_full.current_q_: " << joint_states_full.current_q_.rows());
00041 
00043     KDL::Jacobian jac_full = this->kinematic_extension_->adjustJacobian(jac_chain);
00044     // ROS_INFO_STREAM("jac_full.rows: " << jac_full.rows() << ", jac_full.columns: " << jac_full.columns());
00045 
00047     Vector6d_t v_in_vec;
00048     KDL::Twist v_temp;
00049     v_temp = this->limiters_->enforceLimits(v_in);
00050     tf::twistKDLToEigen(v_temp, v_in_vec);
00051 
00052     Eigen::MatrixXd qdot_out_vec;
00053     retStat = constraint_solver_factory_.calculateJointVelocities(jac_full.data,
00054                                                                   v_in_vec,
00055                                                                   joint_states_full,
00056                                                                   qdot_out_vec);
00057 
00059     KDL::JntArray qdot_out_full(jac_full.columns());
00060     for (int i = 0; i < jac_full.columns(); i++)
00061     {
00062         qdot_out_full(i) = qdot_out_vec(i);
00063         // ROS_INFO_STREAM("qdot_out_full " << i << ": " << qdot_out_full(i));
00064     }
00065     // ROS_INFO_STREAM("qdot_out_full.rows: " << qdot_out_full.rows());
00066 
00068     qdot_out_full = this->limiters_->enforceLimits(qdot_out_full, joint_states_full.current_q_);
00069 
00070     // ROS_INFO_STREAM("qdot_out_full.rows enforced: " << qdot_out_full.rows());
00071     // for (int i = 0; i < jac_full.columns(); i++)
00072     // {
00073     //     ROS_INFO_STREAM("i: " << i << ", qdot_out_full: " << qdot_out_full(i));
00074     // }
00075 
00077     this->kinematic_extension_->processResultExtension(qdot_out_full);
00078 
00080     for (int i = 0; i < jac_chain.columns(); i++)
00081     {
00082         qdot_out(i) = qdot_out_full(i);
00083     }
00084 
00085     return retStat;
00086 }
00087 
00088 void InverseDifferentialKinematicsSolver::resetAll(TwistControllerParams params)
00089 {
00090     this->params_ = params;
00091 
00092     this->kinematic_extension_.reset(KinematicExtensionBuilder::createKinematicExtension(this->params_));
00093     this->limiter_params_ = this->kinematic_extension_->adjustLimiterParams(this->params_.limiter_params);
00094 
00095     this->limiters_.reset(new LimiterContainer(this->limiter_params_));
00096     this->limiters_->init();
00097 
00098     this->task_stack_controller_.clearAllTasks();
00099     if (0 != this->constraint_solver_factory_.resetAll(this->params_, this->limiter_params_))  // params member as reference!!! else process will die!
00100     {
00101         ROS_ERROR("Failed to reset IDK constraint solver after dynamic_reconfigure.");
00102     }
00103 }


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