$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2011, PAL Robotics, S.L. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of PAL Robotics, S.L. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00037 // BIG FAT NOTE: This file was initially intended to be part of a patchset for the KDL, but my views on how to implement IK 00038 // building blocks have changed quite a bit since the initial implementation. However, the functionality provided by 00039 // this file is still useful, and until I get the time to refactor this code, I'm stuck with it. 00040 00041 #ifndef KDL_MATRIXINVERTER_H 00042 #define KDL_MATRIXINVERTER_H 00043 00044 // C++ standard headers 00045 #include <algorithm> 00046 #include <cassert> 00047 00048 // Boost headers 00049 #include <boost/shared_ptr.hpp> 00050 00051 // Eigen headers 00052 #include <Eigen/Dense> 00053 00054 // Forward declarations 00055 namespace Eigen 00056 { 00057 namespace internal 00058 { 00059 template<typename MatrixType> class LsInverseReturnType; 00060 template<typename MatrixType> class DlsInverseReturnType; 00061 template<typename MatrixType> class LsSolveReturnType; 00062 template<typename MatrixType> class DlsSolveReturnType; 00063 } // internal 00064 } // Eigen 00065 00066 namespace KDL 00067 { 00068 00111 00112 // TODO: A note on concurrency 00113 00114 // TODO: Doc solve() methods, remove weights from example 00115 00116 // TODO: Incorporate into JacobiSVD? 00117 00118 // TODO: Add isInitialized 00119 00120 00121 template <typename MatrixType> 00122 class MatrixInverter 00123 { 00124 public: 00125 typedef MatrixType Matrix; 00126 typedef boost::shared_ptr<Matrix> MatrixPtr; 00127 typedef typename Eigen::internal::plain_col_type<Matrix>::type Vector; 00128 typedef typename Matrix::Index Index; 00129 typedef typename Matrix::Scalar Scalar; 00130 typedef typename Eigen::JacobiSVD<Matrix, Eigen::ColPivHouseholderQRPreconditioner> SVD; 00131 typedef Eigen::internal::LsInverseReturnType<Matrix> LsInverseReturnType; 00132 typedef Eigen::internal::DlsInverseReturnType<Matrix> DlsInverseReturnType; 00133 typedef Eigen::internal::LsSolveReturnType<Matrix> LsSolveReturnType; 00134 typedef Eigen::internal::DlsSolveReturnType<Matrix> DlsSolveReturnType; 00135 00139 MatrixInverter(const Index rows, const Index cols); 00140 00154 MatrixInverter(const Matrix& A); 00155 00158 MatrixInverter& compute(const Matrix& A); 00159 00162 LsInverseReturnType inverse() {return lsInverse();} 00163 00168 LsInverseReturnType lsInverse() {return LsInverseReturnType(*this);} 00169 00174 DlsInverseReturnType dlsInverse() {return DlsInverseReturnType(*this);} 00175 00178 LsSolveReturnType solve(const Vector& b) {return lsSolve(b);} 00179 00182 LsSolveReturnType lsSolve(const Vector& b) {return LsSolveReturnType(b, *this);} 00183 00186 DlsSolveReturnType dlsSolve(const Vector& b) {return DlsSolveReturnType(b, *this);} 00187 00190 void setLsInverseThreshold(const Scalar eps) {lsEps_ = eps;} 00191 00194 Scalar getLsInverseThreshold() const {return lsEps_;} 00195 00211 void setDlsInverseThreshold(const Scalar dampEps) {dlsEps_ = dampEps;} 00212 00215 Scalar getDlsInverseThreshold() const {return dlsEps_;} 00216 00219 void setMaxDamping(const Scalar dampMax) {dampMax_ = dampMax;} 00220 00223 Scalar getMaxDamping() const {return dampMax_;} 00224 00225 private: 00226 SVD svd_; 00227 Scalar lsEps_; 00228 Scalar dlsEps_; 00229 Scalar dampMax_; 00230 00231 // Preallocated instances to allow execution in contexts where heap allocations are forbidden 00232 Matrix pinv_; 00233 Vector solve1_; 00234 Vector solve2_; 00235 00237 void allocate(const Index rows, const Index cols); 00238 00240 Index nonzeroSingularValues() const; 00241 00244 Scalar computeDampingSq(const Vector& S) const; 00245 00246 friend class Eigen::internal::LsInverseReturnType<MatrixType>; 00247 friend class Eigen::internal::DlsInverseReturnType<MatrixType>; 00248 friend class Eigen::internal::LsSolveReturnType<MatrixType>; 00249 friend class Eigen::internal::DlsSolveReturnType<MatrixType>; 00250 }; 00251 00252 template <typename MatrixType> 00253 MatrixInverter<MatrixType>::MatrixInverter(const Index rows, const Index cols) 00254 { 00255 allocate(rows, cols); 00256 } 00257 00258 template <typename MatrixType> 00259 MatrixInverter<MatrixType>::MatrixInverter(const Matrix& A) 00260 { 00261 allocate(A.rows(), A.cols()); 00262 compute(A); 00263 } 00264 00265 template <typename MatrixType> 00266 inline void MatrixInverter<MatrixType>::allocate(const Index rows, const Index cols) 00267 { 00268 if (rows == 0 || cols == 0) throw; // TODO: Throw what? Decide when to throw, when to assert 00269 00270 svd_ = SVD(rows, cols, Eigen::ComputeThinU | Eigen::ComputeThinV); 00271 lsEps_ = Eigen::NumTraits<Scalar>::epsilon(); 00272 dlsEps_ = 1e3 * Eigen::NumTraits<Scalar>::epsilon(); // TODO: Is this a sensible default? 00273 dampMax_ = 0.1; // TODO: Is this a sensible default? 00274 const Index minDim = std::min(rows, cols); 00275 pinv_ = Matrix(minDim, minDim); 00276 solve1_ = Vector(minDim); 00277 solve2_ = Vector(minDim); 00278 } 00279 00280 template <typename MatrixType> 00281 inline MatrixInverter<MatrixType>& MatrixInverter<MatrixType>::compute(const Matrix& A) 00282 { 00283 // Check preconditions 00284 assert(A.rows() == svd_.rows() && A.cols() == svd_.cols() && 00285 "Size mismatch between MatrixInverter and input matrix."); 00286 00287 // Compute SVD of input matrix 00288 svd_.compute(A); 00289 return *this; 00290 } 00291 00292 template <typename MatrixType> 00293 inline typename MatrixInverter<MatrixType>::Index MatrixInverter<MatrixType>::nonzeroSingularValues() const 00294 { 00295 const SVD& svd = svd_; 00296 const Vector& S = svd.singularValues(); 00297 const Index end = svd.nonzeroSingularValues(); // Number of singular values that are not _exactly_ zero 00298 00299 Index id; 00300 // Loop going from smallest _nonzero_ singular value to first one larger than the prescribed tolerance 00301 for (id = end; id > 0; --id) { if (S(id -1) >= lsEps_ ) {break;} } 00302 return id; 00303 } 00304 00305 template <typename MatrixType> 00306 inline typename MatrixInverter<MatrixType>::Scalar 00307 MatrixInverter<MatrixType>::computeDampingSq(const Vector& S) const 00308 { 00309 const Scalar Smin = S(S.size() - 1); // Smallest singular value 00310 return (Smin >= dlsEps_) ? 0.0 : (1.0 - (Smin * Smin) / (dlsEps_ * dlsEps_)) * (dampMax_ * dampMax_); 00311 } 00312 00313 } // KDL 00314 00315 00316 namespace Eigen 00317 { 00318 namespace internal 00319 { 00320 00321 template<typename MatrixType> 00322 struct traits<LsInverseReturnType<MatrixType> > {typedef typename MatrixType::PlainObject ReturnType;}; 00323 00328 template<typename MatrixType> 00329 class LsInverseReturnType : public Eigen::ReturnByValue<LsInverseReturnType<MatrixType> > 00330 { 00331 public: 00332 typedef MatrixType Matrix; 00333 typedef typename Matrix::Index Index; 00334 typedef typename Matrix::Scalar Scalar; 00335 typedef typename KDL::MatrixInverter<MatrixType> MatrixInverter; 00336 typedef typename MatrixInverter::Vector Vector; 00337 typedef typename MatrixInverter::SVD SVD; 00338 00340 LsInverseReturnType(MatrixInverter& inverter) : inverter_(inverter) {} 00341 00343 template <typename ResultType> void evalTo(ResultType& result) const; 00344 00345 Index rows() const { return inverter_.svd_.cols(); } 00346 Index cols() const { return inverter_.svd_.rows(); } 00347 00348 private: 00349 MatrixInverter& inverter_; 00350 }; 00351 00352 template<typename MatrixType> 00353 struct traits<DlsInverseReturnType<MatrixType> > {typedef typename MatrixType::PlainObject ReturnType;}; 00354 00359 template<typename MatrixType> 00360 class DlsInverseReturnType : public Eigen::ReturnByValue<DlsInverseReturnType<MatrixType> > 00361 { 00362 public: 00363 typedef MatrixType Matrix; 00364 typedef typename Matrix::Index Index; 00365 typedef typename Matrix::Scalar Scalar; 00366 typedef typename KDL::MatrixInverter<MatrixType> MatrixInverter; 00367 typedef typename MatrixInverter::Vector Vector; 00368 typedef typename MatrixInverter::SVD SVD; 00369 00371 DlsInverseReturnType(MatrixInverter& inverter) : inverter_(inverter) {} 00372 00374 template <typename ResultType> void evalTo(ResultType& result) const; 00375 00376 Index rows() const { return inverter_.svd_.cols(); } 00377 Index cols() const { return inverter_.svd_.rows(); } 00378 00379 private: 00380 MatrixInverter& inverter_; 00381 }; 00382 00383 template<typename MatrixType> 00384 struct traits<LsSolveReturnType<MatrixType> > {typedef typename MatrixType::PlainObject ReturnType;}; 00385 00390 template<typename MatrixType> 00391 class LsSolveReturnType : public Eigen::ReturnByValue<LsSolveReturnType<MatrixType> > 00392 { 00393 public: 00394 typedef MatrixType Matrix; 00395 typedef typename Matrix::Index Index; 00396 typedef typename Matrix::Scalar Scalar; 00397 typedef typename KDL::MatrixInverter<MatrixType> MatrixInverter; 00398 typedef typename MatrixInverter::Vector Vector; 00399 typedef typename MatrixInverter::SVD SVD; 00400 00403 LsSolveReturnType(const Vector& b, 00404 MatrixInverter& inverter) : b_(b), inverter_(inverter) {} 00405 00407 template <typename ResultType> void evalTo(ResultType& result) const; 00408 00409 Index rows() const { return inverter_.svd_.cols(); } 00410 Index cols() const { return 1; } 00411 00412 private: 00413 const Vector& b_; 00414 MatrixInverter& inverter_; 00415 }; 00416 00417 template<typename MatrixType> 00418 struct traits<DlsSolveReturnType<MatrixType> > {typedef typename MatrixType::PlainObject ReturnType;}; 00419 00424 template<typename MatrixType> 00425 class DlsSolveReturnType : public Eigen::ReturnByValue<DlsSolveReturnType<MatrixType> > 00426 { 00427 public: 00428 typedef MatrixType Matrix; 00429 typedef typename Matrix::Index Index; 00430 typedef typename Matrix::Scalar Scalar; 00431 typedef typename KDL::MatrixInverter<MatrixType> MatrixInverter; 00432 typedef typename MatrixInverter::Vector Vector; 00433 typedef typename MatrixInverter::SVD SVD; 00434 00437 DlsSolveReturnType(const Vector& b, 00438 MatrixInverter& inverter) : b_(b), inverter_(inverter) {} 00439 00441 template <typename ResultType> void evalTo(ResultType& result) const; 00442 00443 Index rows() const { return inverter_.svd_.cols(); } 00444 Index cols() const { return 1; } 00445 00446 private: 00447 const Vector& b_; 00448 MatrixInverter& inverter_; 00449 }; 00450 00451 template <typename MatrixType> template <typename ResultType> 00452 void LsInverseReturnType<MatrixType>::evalTo(ResultType& result) const 00453 { 00454 // Work matrix 00455 Matrix& T = inverter_.pinv_; 00456 00457 // SVD details 00458 const SVD& svd = inverter_.svd_; 00459 const Index rows = svd.rows(); 00460 const Index cols = svd.cols(); 00461 00462 const Vector& S = svd.singularValues(); // Sorted in decreasing order 00463 const Matrix& U = svd.matrixU(); 00464 const Matrix& V = svd.matrixV(); 00465 00466 // Perform V Sinv U' subject to these optimizations: 00467 // - Space: Use the smallest possible temporaries. This is purpose of the (rows < cols) test 00468 // - Time: Exclude unused blocks of U, S, V and work matrices from the computation. They correspond to the 00469 // elements that are multiplied by the entries of S cutoff to zero. 00470 const Index cutoffSize = inverter_.nonzeroSingularValues(); 00471 if (rows < cols) 00472 { 00473 T.topLeftCorner(cutoffSize, rows).noalias() = 00474 S.head(cutoffSize).array().inverse().matrix().asDiagonal() * U.leftCols(cutoffSize).transpose(); // Sinv U' 00475 result.noalias() = V.leftCols(cutoffSize) * T.topLeftCorner(cutoffSize, rows); // V Sinv U' 00476 } 00477 else 00478 { 00479 T.topLeftCorner(cols, cutoffSize).noalias() = 00480 V.leftCols(cutoffSize) * S.head(cutoffSize).array().inverse().matrix().asDiagonal(); // V Sinv 00481 result.noalias() = T.topLeftCorner(cols, cutoffSize) * U.leftCols(cutoffSize).transpose(); // V Sinv U' 00482 } 00483 } 00484 00485 template <typename MatrixType> template <typename ResultType> 00486 void DlsInverseReturnType<MatrixType>::evalTo(ResultType& result) const 00487 { 00488 // Work matrix 00489 Matrix& T = inverter_.pinv_; 00490 00491 // SVD details 00492 const SVD& svd = inverter_.svd_; 00493 const Index rows = svd.rows(); 00494 const Index cols = svd.cols(); 00495 00496 const Vector& S = svd.singularValues(); // Sorted in decreasing order 00497 const Matrix& U = svd.matrixU(); 00498 const Matrix& V = svd.matrixV(); 00499 00500 // Damped least-squares inverse: V Sinv U' 00501 const Scalar dampSq = inverter_.computeDampingSq(S); 00502 const Index minDim = std::min(rows, cols); 00503 if (rows < cols) 00504 { 00505 T.topLeftCorner(minDim, minDim).noalias() = 00506 (S.array() / (S.array().square() + dampSq)).matrix().asDiagonal() * U.transpose(); // Sinv U' 00507 result.noalias() = V * T.topLeftCorner(minDim, minDim); // V Sinv U' 00508 } 00509 else 00510 { 00511 T.topLeftCorner(minDim, minDim).noalias() = 00512 V * (S.array() / (S.array().square() + dampSq)).matrix().asDiagonal(); // V Sinv 00513 result.noalias() = T.topLeftCorner(minDim, minDim) * U.transpose(); // V Sinv U' 00514 } 00515 } 00516 00517 template <typename MatrixType> template <typename ResultType> 00518 inline void LsSolveReturnType<MatrixType>::evalTo(ResultType& result) const 00519 { 00520 // Work vectors 00521 Vector& vec1 = inverter_.solve1_; 00522 Vector& vec2 = inverter_.solve2_; 00523 00524 // SVD details 00525 const SVD& svd = inverter_.svd_; 00526 const Vector& S = svd.singularValues(); // Sorted in decreasing order 00527 const Matrix& U = svd.matrixU(); 00528 const Matrix& V = svd.matrixV(); 00529 00530 // Perform V Sinv U' b subject to these optimizations: 00531 // - Space, time: Favor matrix-vector products over matrix-matrix products. 00532 // - Time: Exclude unused blocks of U, S, V and work matrices from the computation. They correspond to the 00533 // elements that are multiplied by the entries of S cutoff to zero. 00534 const Index cutoffSize = inverter_.nonzeroSingularValues(); 00535 00536 vec1.head(cutoffSize).noalias() = U.leftCols(cutoffSize).transpose() * b_; // U' b 00537 vec2.head(cutoffSize).noalias() = S.head(cutoffSize).array().inverse().matrix().asDiagonal() * 00538 vec1.head(cutoffSize); // Sinv U' b 00539 result.noalias() = V.leftCols(cutoffSize) * vec2.head(cutoffSize); // V Sinv U' b 00540 } 00541 00542 template <typename MatrixType> template <typename ResultType> 00543 inline void DlsSolveReturnType<MatrixType>::evalTo(ResultType& result) const 00544 { 00545 // Work vectors 00546 Vector& vec1 = inverter_.solve1_; 00547 Vector& vec2 = inverter_.solve2_; 00548 00549 // SVD details 00550 const SVD& svd = inverter_.svd_; 00551 const Vector& S = svd.singularValues(); // Sorted in decreasing order 00552 const Matrix& U = svd.matrixU(); 00553 const Matrix& V = svd.matrixV(); 00554 00555 // Perform V Sinv U' b subject to these optimizations: 00556 // Space, time: Favor matrix-vector products over matrix-matrix products. 00557 const Scalar dampSq = inverter_.computeDampingSq(S); 00558 00559 vec1.noalias() = U.transpose() * b_; // U' b 00560 vec2.noalias() = (S.array() / (S.array().square() + dampSq)).matrix().asDiagonal() * vec1; // Sinv U' b 00561 result.noalias() = V * vec2; // V Sinv U' b 00562 } 00563 00564 } // Eigen 00565 } // internal 00566 00567 #endif // KDL_MATRIXINVERTER_H