$search
Least-squares and damped least-squares inverse computation for rectangular, real-valued matrices. More...
#include <matrix_inverter.h>
Public Types | |
| typedef Eigen::internal::DlsInverseReturnType < Matrix > | DlsInverseReturnType |
| typedef Eigen::internal::DlsSolveReturnType < Matrix > | DlsSolveReturnType |
| typedef Matrix::Index | Index |
| typedef Eigen::internal::LsInverseReturnType < Matrix > | LsInverseReturnType |
| typedef Eigen::internal::LsSolveReturnType < Matrix > | LsSolveReturnType |
| typedef MatrixType | Matrix |
| typedef boost::shared_ptr< Matrix > | MatrixPtr |
| typedef Matrix::Scalar | Scalar |
| typedef Eigen::JacobiSVD < Matrix, Eigen::ColPivHouseholderQRPreconditioner > | SVD |
| typedef Eigen::internal::plain_col_type < Matrix >::type | Vector |
Public Member Functions | |
| MatrixInverter & | compute (const Matrix &A) |
| DlsInverseReturnType | dlsInverse () |
| Compute the damped least-squares inverse. | |
| DlsSolveReturnType | dlsSolve (const Vector &b) |
| Scalar | getDlsInverseThreshold () const |
| Scalar | getLsInverseThreshold () const |
| Scalar | getMaxDamping () const |
| LsInverseReturnType | inverse () |
| Convenience alias for lsInverse(const Vector&). | |
| LsInverseReturnType | lsInverse () |
| Compute the least-squares inverse. | |
| LsSolveReturnType | lsSolve (const Vector &b) |
| MatrixInverter (const Matrix &A) | |
| Input matrix constructor. Using this constructor, like so. | |
| MatrixInverter (const Index rows, const Index cols) | |
| Problem dimension constructor. Preallocates all data structures so that compute(const Matrix&), lsInverse() and dlsInverse() are heap-allocation-free. | |
| void | setDlsInverseThreshold (const Scalar dampEps) |
| void | setLsInverseThreshold (const Scalar eps) |
| void | setMaxDamping (const Scalar dampMax) |
| LsSolveReturnType | solve (const Vector &b) |
| Convenience alias for lsSolve(const Vector&). | |
Private Member Functions | |
| void | allocate (const Index rows, const Index cols) |
| Initialize default parameters. This method is common to all constructors. | |
| Scalar | computeDampingSq (const Vector &S) const |
| Index | nonzeroSingularValues () const |
Private Attributes | |
| Scalar | dampMax_ |
| Maximum damping. | |
| Scalar | dlsEps_ |
| Threshold for smallest nonzero singular value used in damped least-squares inverse. | |
| Scalar | lsEps_ |
| Threshold for smallest nonzero singular value used in least-squares inverse. | |
| Matrix | pinv_ |
| Work matrix used when computing inverses explicitly. | |
| Vector | solve1_ |
| Work vector used when solving the associated linear system. | |
| Vector | solve2_ |
| Work vector used when solving the associated linear system. | |
| SVD | svd_ |
| Singular Value Decomposition. | |
Friends | |
| class | Eigen::internal::DlsInverseReturnType< MatrixType > |
| class | Eigen::internal::DlsSolveReturnType< MatrixType > |
| class | Eigen::internal::LsInverseReturnType< MatrixType > |
| class | Eigen::internal::LsSolveReturnType< MatrixType > |
Least-squares and damped least-squares inverse computation for rectangular, real-valued matrices.
| MatrixType | Type of underlying dense matrix. This class uses the Singular Value Decomposition (SVD) for computing the inverse of a matrix. Let be the SVD of a n-by-p, real-valued matrix, and let m be the smaller value among n and p, its inverse can be computed as . This class allows two ways of computing : TODO: Finish
|
It's important to note that a single SVD can be used to compute both the least-squares and damped least-squares inverses of a matrix. The following code exemplifies typical usage scenarios:
typedef Eigen::MatrixXd Matrix; typedef boost::shared_ptr<Matrix> MatrixPtr; typedef Eigen::VectorXd Vector; const int rows = 5; const int cols = 10; Matrix A = Matrix::Random(rows, cols); Matrix Ainv(rows, cols); // Different use cases of increasing complexity // Case 1: Use default parameters, compute least-squares inverse Ainv = MatrixInverter<Matrix>(A).lsInverse(); // Handy for one-off usage Ainv = MatrixInverter<Matrix>(A).inverse(); // Same as above, inverse() is a convenience alias for lsInverse() // Case 2: similar to case 1, but with resource preallocation KDL::MatrixInverter<Matrix> inv(rows, cols); // Preallocate resources Ainv = inv.compute(A).inverse(); // No allocations take place here // Case 3: Use custom parameters inv.setLsInverseThreshold(1e-5); Ainv = inv.compute(A).lsInverse(); // Case 4: Compute both least-squares amd damped least-squares inverses inv.setDlsInverseThreshold(0.1); // Damping activation threshold inv.compute(A); // Using the same SVD... Ainv = inv.lsInverse(); // Compute the least-squares... Matrix Adinv = inv.dlsInverse(); // and damped least-squares inverses
Definition at line 122 of file matrix_inverter.h.
| typedef Eigen::internal::DlsInverseReturnType<Matrix> KDL::MatrixInverter< MatrixType >::DlsInverseReturnType |
Definition at line 132 of file matrix_inverter.h.
| typedef Eigen::internal::DlsSolveReturnType<Matrix> KDL::MatrixInverter< MatrixType >::DlsSolveReturnType |
Definition at line 134 of file matrix_inverter.h.
| typedef Matrix::Index KDL::MatrixInverter< MatrixType >::Index |
Definition at line 128 of file matrix_inverter.h.
| typedef Eigen::internal::LsInverseReturnType<Matrix> KDL::MatrixInverter< MatrixType >::LsInverseReturnType |
Definition at line 131 of file matrix_inverter.h.
| typedef Eigen::internal::LsSolveReturnType<Matrix> KDL::MatrixInverter< MatrixType >::LsSolveReturnType |
Definition at line 133 of file matrix_inverter.h.
| typedef MatrixType KDL::MatrixInverter< MatrixType >::Matrix |
Definition at line 125 of file matrix_inverter.h.
| typedef boost::shared_ptr<Matrix> KDL::MatrixInverter< MatrixType >::MatrixPtr |
Definition at line 126 of file matrix_inverter.h.
| typedef Matrix::Scalar KDL::MatrixInverter< MatrixType >::Scalar |
Definition at line 129 of file matrix_inverter.h.
| typedef Eigen::JacobiSVD<Matrix, Eigen::ColPivHouseholderQRPreconditioner> KDL::MatrixInverter< MatrixType >::SVD |
Definition at line 130 of file matrix_inverter.h.
| typedef Eigen::internal::plain_col_type<Matrix>::type KDL::MatrixInverter< MatrixType >::Vector |
Definition at line 127 of file matrix_inverter.h.
| KDL::MatrixInverter< MatrixType >::MatrixInverter | ( | const Index | rows, | |
| const Index | cols | |||
| ) | [inline] |
Problem dimension constructor. Preallocates all data structures so that compute(const Matrix&), lsInverse() and dlsInverse() are heap-allocation-free.
Definition at line 253 of file matrix_inverter.h.
| KDL::MatrixInverter< MatrixType >::MatrixInverter | ( | const Matrix & | A | ) | [inline] |
Input matrix constructor. Using this constructor, like so.
Matrix A(rows, cols); MatrixInverter<Matrix> inv(A);
is a more compact and equivalent way of doing
Matrix A(rows, cols); MatrixInverter<Matrix> inv(rows, cols); inv.compute();
Definition at line 259 of file matrix_inverter.h.
| void KDL::MatrixInverter< MatrixType >::allocate | ( | const Index | rows, | |
| const Index | cols | |||
| ) | [inline, private] |
Initialize default parameters. This method is common to all constructors.
Definition at line 266 of file matrix_inverter.h.
| MatrixInverter< MatrixType > & KDL::MatrixInverter< MatrixType >::compute | ( | const Matrix & | A | ) | [inline] |
| A | Matrix to invert. |
Definition at line 281 of file matrix_inverter.h.
| MatrixInverter< MatrixType >::Scalar KDL::MatrixInverter< MatrixType >::computeDampingSq | ( | const Vector & | S | ) | const [inline, private] |
| S | Vector of singular values. |
Definition at line 307 of file matrix_inverter.h.
| DlsInverseReturnType KDL::MatrixInverter< MatrixType >::dlsInverse | ( | ) | [inline] |
Compute the damped least-squares inverse.
Definition at line 174 of file matrix_inverter.h.
| DlsSolveReturnType KDL::MatrixInverter< MatrixType >::dlsSolve | ( | const Vector & | b | ) | [inline] |
TODO: Doc!
Definition at line 186 of file matrix_inverter.h.
| Scalar KDL::MatrixInverter< MatrixType >::getDlsInverseThreshold | ( | ) | const [inline] |
Definition at line 215 of file matrix_inverter.h.
| Scalar KDL::MatrixInverter< MatrixType >::getLsInverseThreshold | ( | ) | const [inline] |
Definition at line 194 of file matrix_inverter.h.
| Scalar KDL::MatrixInverter< MatrixType >::getMaxDamping | ( | ) | const [inline] |
Definition at line 223 of file matrix_inverter.h.
| LsInverseReturnType KDL::MatrixInverter< MatrixType >::inverse | ( | ) | [inline] |
Convenience alias for lsInverse(const Vector&).
Definition at line 162 of file matrix_inverter.h.
| LsInverseReturnType KDL::MatrixInverter< MatrixType >::lsInverse | ( | ) | [inline] |
Compute the least-squares inverse.
Definition at line 168 of file matrix_inverter.h.
| LsSolveReturnType KDL::MatrixInverter< MatrixType >::lsSolve | ( | const Vector & | b | ) | [inline] |
TODO: Doc!
Definition at line 182 of file matrix_inverter.h.
| MatrixInverter< MatrixType >::Index KDL::MatrixInverter< MatrixType >::nonzeroSingularValues | ( | ) | const [inline, private] |
Definition at line 293 of file matrix_inverter.h.
| void KDL::MatrixInverter< MatrixType >::setDlsInverseThreshold | ( | const Scalar | dampEps | ) | [inline] |
| dampEps | Threshold for smallest nonzero singular value used when computing the damped least-squares inverse. Valid values are in the range [0,1]. |
is computed as [1]:
is the smallestsingular values of a matrix
, and
is the maximum damping (see setMaxDamping(const Scalar) ).[1] S. Chiaverini, O. Egeland, R.K. Kanestrom: Achieving user-defined accuracy with damped least-squares inverse kinematics, ICAR 1991 pp. 672–677
Definition at line 211 of file matrix_inverter.h.
| void KDL::MatrixInverter< MatrixType >::setLsInverseThreshold | ( | const Scalar | eps | ) | [inline] |
| eps | Threshold for smallest nonzero singular value used when computing the least-squares inverse. Valid values are in the range [0,1]. |
Definition at line 190 of file matrix_inverter.h.
| void KDL::MatrixInverter< MatrixType >::setMaxDamping | ( | const Scalar | dampMax | ) | [inline] |
| dampMax | Maximum damping used when computing the damped least-squares inverse. |
Definition at line 219 of file matrix_inverter.h.
| LsSolveReturnType KDL::MatrixInverter< MatrixType >::solve | ( | const Vector & | b | ) | [inline] |
Convenience alias for lsSolve(const Vector&).
Definition at line 178 of file matrix_inverter.h.
friend class Eigen::internal::DlsInverseReturnType< MatrixType > [friend] |
Definition at line 247 of file matrix_inverter.h.
friend class Eigen::internal::DlsSolveReturnType< MatrixType > [friend] |
Definition at line 249 of file matrix_inverter.h.
friend class Eigen::internal::LsInverseReturnType< MatrixType > [friend] |
Definition at line 246 of file matrix_inverter.h.
friend class Eigen::internal::LsSolveReturnType< MatrixType > [friend] |
Definition at line 248 of file matrix_inverter.h.
Scalar KDL::MatrixInverter< MatrixType >::dampMax_ [private] |
Maximum damping.
Definition at line 229 of file matrix_inverter.h.
Scalar KDL::MatrixInverter< MatrixType >::dlsEps_ [private] |
Threshold for smallest nonzero singular value used in damped least-squares inverse.
Definition at line 228 of file matrix_inverter.h.
Scalar KDL::MatrixInverter< MatrixType >::lsEps_ [private] |
Threshold for smallest nonzero singular value used in least-squares inverse.
Definition at line 227 of file matrix_inverter.h.
Matrix KDL::MatrixInverter< MatrixType >::pinv_ [private] |
Work matrix used when computing inverses explicitly.
Definition at line 232 of file matrix_inverter.h.
Vector KDL::MatrixInverter< MatrixType >::solve1_ [private] |
Work vector used when solving the associated linear system.
Definition at line 233 of file matrix_inverter.h.
Vector KDL::MatrixInverter< MatrixType >::solve2_ [private] |
Work vector used when solving the associated linear system.
Definition at line 234 of file matrix_inverter.h.
SVD KDL::MatrixInverter< MatrixType >::svd_ [private] |
Singular Value Decomposition.
Definition at line 226 of file matrix_inverter.h.