weighted_least_norm_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 "cob_twist_controller/constraint_solvers/solvers/weighted_least_norm_solver.h"
00019 
00025 Eigen::MatrixXd WeightedLeastNormSolver::solve(const Vector6d_t& in_cart_velocities,
00026                                                const JointStates& joint_states)
00027 {
00028     Eigen::MatrixXd W_WLN = this->calculateWeighting(joint_states);
00029     // for the following formulas see Chan paper ISSN 1042-296X [Page 288]
00030     Eigen::MatrixXd root_W_WLN =  W_WLN.cwiseSqrt();            // element-wise sqrt -> ok because diag matrix W^(1/2)
00031     Eigen::MatrixXd inv_root_W_WLN =  root_W_WLN.inverse();     // -> W^(-1/2)
00032 
00033     // SVD of JLA weighted Jacobian: Damping will be done later in calculatePinvJacobianBySVD for pseudo-inverse Jacobian with additional truncation etc.
00034     Eigen::MatrixXd weighted_jacobian = this->jacobian_data_ * inv_root_W_WLN;
00035     Eigen::MatrixXd pinv = pinv_calc_.calculate(this->params_, this->damping_, weighted_jacobian);
00036 
00037     // Take care: W^(1/2) * q_dot = weighted_pinv_J * x_dot -> One must consider the weighting!!!
00038     Eigen::MatrixXd qdots_out = inv_root_W_WLN * pinv * in_cart_velocities;
00039     return qdots_out;
00040 }
00041 
00045 Eigen::MatrixXd WeightedLeastNormSolver::calculateWeighting(const JointStates& joint_states) const
00046 {
00047     uint32_t cols = this->jacobian_data_.cols();
00048     Eigen::VectorXd weighting = Eigen::VectorXd::Ones(cols);
00049     return weighting.asDiagonal();
00050 }


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