Skip to content

Commit 092ae94

Browse files
committed
More efficient computation of PseudoInverse
Considering S as a rectangular matrix when only the diagonal elements are relevant is vasting computing resources in matrix multiplication.
1 parent f6c2b35 commit 092ae94

File tree

1 file changed

+6
-8
lines changed

1 file changed

+6
-8
lines changed

franka_example_controllers/include/franka_example_controllers/pseudo_inversion.h

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -16,15 +16,13 @@ namespace franka_example_controllers {
1616
inline void pseudoInverse(const Eigen::MatrixXd& M_, Eigen::MatrixXd& M_pinv_, bool damped = true) {
1717
double lambda_ = damped ? 0.2 : 0.0;
1818

19-
Eigen::JacobiSVD<Eigen::MatrixXd> svd(M_, Eigen::ComputeFullU | Eigen::ComputeFullV);
20-
Eigen::JacobiSVD<Eigen::MatrixXd>::SingularValuesType sing_vals_ = svd.singularValues();
21-
Eigen::MatrixXd S_ = M_; // copying the dimensions of M_, its content is not needed.
22-
S_.setZero();
19+
Eigen::JacobiSVD<Eigen::MatrixXd> svd(M_, Eigen::ComputeThinU | Eigen::ComputeThinV);
20+
Eigen::VectorXd sing_vals_ = svd.singularValues();
21+
for (unsigned int i = 0; i < sing_vals_.size(); ++i)
22+
sing_vals_[i] = sing_vals_[i] / (sing_vals_[i] * sing_vals_[i] + lambda_ * lambda_);
2323

24-
for (int i = 0; i < sing_vals_.size(); i++)
25-
S_(i, i) = (sing_vals_(i)) / (sing_vals_(i) * sing_vals_(i) + lambda_ * lambda_);
26-
27-
M_pinv_ = Eigen::MatrixXd(svd.matrixV() * S_.transpose() * svd.matrixU().transpose());
24+
M_pinv_.noalias() =
25+
Eigen::MatrixXd(svd.matrixV() * (sing_vals_.asDiagonal() * svd.matrixU().transpose()));
2826
}
2927

3028
} // namespace franka_example_controllers

0 commit comments

Comments
 (0)