weighted_least_norm_solver.cpp
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 
19 
25 Eigen::MatrixXd WeightedLeastNormSolver::solve(const Vector6d_t& in_cart_velocities,
26  const JointStates& joint_states)
27 {
28  Eigen::MatrixXd W_WLN = this->calculateWeighting(joint_states);
29  // for the following formulas see Chan paper ISSN 1042-296X [Page 288]
30  Eigen::MatrixXd root_W_WLN = W_WLN.cwiseSqrt(); // element-wise sqrt -> ok because diag matrix W^(1/2)
31  Eigen::MatrixXd inv_root_W_WLN = root_W_WLN.inverse(); // -> W^(-1/2)
32 
33  // SVD of JLA weighted Jacobian: Damping will be done later in calculatePinvJacobianBySVD for pseudo-inverse Jacobian with additional truncation etc.
34  Eigen::MatrixXd weighted_jacobian = this->jacobian_data_ * inv_root_W_WLN;
35  Eigen::MatrixXd pinv = pinv_calc_.calculate(this->params_, this->damping_, weighted_jacobian);
36 
37  // Take care: W^(1/2) * q_dot = weighted_pinv_J * x_dot -> One must consider the weighting!!!
38  Eigen::MatrixXd qdots_out = inv_root_W_WLN * pinv * in_cart_velocities;
39  return qdots_out;
40 }
41 
45 Eigen::MatrixXd WeightedLeastNormSolver::calculateWeighting(const JointStates& joint_states) const
46 {
47  uint32_t cols = this->jacobian_data_.cols();
48  Eigen::VectorXd weighting = Eigen::VectorXd::Ones(cols);
49  return weighting.asDiagonal();
50 }
boost::shared_ptr< DampingBase > damping_
References the current Jacobian (matrix data only).
Eigen::Matrix< double, 6, 1 > Vector6d_t
Matrix6Xd_t jacobian_data_
References the limiter parameters (up-to-date according to KinematicExtension).
PInvBySVD pinv_calc_
The currently set damping method.
const TwistControllerParams & params_
Set of constraints.
virtual Eigen::MatrixXd calculate(const Eigen::MatrixXd &jacobian) const
virtual Eigen::MatrixXd calculateWeighting(const JointStates &joint_states) const
virtual Eigen::MatrixXd solve(const Vector6d_t &in_cart_velocities, const JointStates &joint_states)


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:01