#include <Eigen/Dense>

Go to the source code of this file.
| Namespaces | |
| lvr2 | |
| Typedefs | |
| template<typename T > | |
| using | lvr2::Distortion = Eigen::Matrix< T, 6, 1 > | 
| Distortion Parameters.  More... | |
| using | lvr2::Distortiond = Distortion< double > | 
| Distortion Parameters (double precision)  More... | |
| using | lvr2::Distortionf = Distortion< float > | 
| Distortion Parameters (single precision)  More... | |
| template<typename T > | |
| using | lvr2::Extrinsics = Eigen::Matrix< T, 4, 4 > | 
| 4x4 extrinsic calibration  More... | |
| using | lvr2::Extrinsicsd = Extrinsics< double > | 
| 4x4 extrinsic calibration (double precision)  More... | |
| using | lvr2::Extrinsicsf = Extrinsics< float > | 
| 4x4 extrinsic calibration (single precision)  More... | |
| template<typename T > | |
| using | lvr2::Intrinsics = Eigen::Matrix< T, 3, 3 > | 
| 4x4 extrinsic calibration  More... | |
| using | lvr2::Intrinsicsd = Intrinsics< double > | 
| 4x4 extrinsic calibration (double precision)  More... | |
| using | lvr2::Intrinsicsf = Intrinsics< float > | 
| 4x4 intrinsic calibration (single precision)  More... | |
| using | lvr2::Matrix3dRM = Matrix3RM< double > | 
| 3x3 row major matrix with double scalars  More... | |
| using | lvr2::Matrix3fRM = Matrix3RM< float > | 
| 3x3 row major matrix with float scalars  More... | |
| template<typename T > | |
| using | lvr2::Matrix3RM = Eigen::Matrix< T, 3, 3, Eigen::RowMajor > | 
| General alias for row major 3x3 matrices.  More... | |
| using | lvr2::Matrix4d = Eigen::Matrix4d | 
| Eigen 4x4 matrix, double precision.  More... | |
| using | lvr2::Matrix4dRM = Matrix4RM< double > | 
| 4x4 row major matrix with double scalars  More... | |
| using | lvr2::Matrix4f = Eigen::Matrix4f | 
| Eigen 4x4 matrix, single precision.  More... | |
| using | lvr2::Matrix4fRM = Matrix4RM< float > | 
| 4x4 row major matrix with float scalars  More... | |
| template<typename T > | |
| using | lvr2::Matrix4RM = Eigen::Matrix< T, 4, 4, Eigen::RowMajor > | 
| General alias for row major 4x4 matrices.  More... | |
| using | lvr2::Matrix6d = Eigen::Matrix< double, 6, 6 > | 
| 6D matrix double precision  More... | |
| using | lvr2::Matrix6f = Eigen::Matrix< float, 6, 6 > | 
| 6D Matrix, single precision  More... | |
| template<typename T > | |
| using | lvr2::Rotation = Eigen::Matrix< T, 3, 3 > | 
| General 3x3 rotation matrix.  More... | |
| using | lvr2::Rotationd = Rotation< double > | 
| Double precision 3x3 rotation matrix.  More... | |
| using | lvr2::Rotationf = Rotation< float > | 
| Single precision 3x3 rotation matrix.  More... | |
| template<typename T > | |
| using | lvr2::Transform = Eigen::Matrix< T, 4, 4 > | 
| General 4x4 transformation matrix (4x4)  More... | |
| using | lvr2::Transformd = Transform< double > | 
| 4x4 double precision transformation matrix  More... | |
| using | lvr2::Transformf = Transform< float > | 
| 4x4 single precision transformation matrix  More... | |
| template<typename T > | |
| using | lvr2::Vector2 = Eigen::Matrix< T, 2, 1 > | 
| Eigen 2D vector.  More... | |
| using | lvr2::Vector2d = Eigen::Vector2d | 
| Eigen 2D vector, double precision.  More... | |
| using | lvr2::Vector2f = Eigen::Vector2f | 
| Eigen 2D vector, single precision.  More... | |
| template<typename T > | |
| using | lvr2::Vector3 = Eigen::Matrix< T, 3, 1 > | 
| Eigen 3D vector.  More... | |
| using | lvr2::Vector3d = Eigen::Vector3d | 
| Eigen 3D vector, double precision.  More... | |
| using | lvr2::Vector3f = Eigen::Vector3f | 
| Eigen 3D vector, single precision.  More... | |
| using | lvr2::Vector3i = Eigen::Vector3i | 
| Eigen 3D vector, integer.  More... | |
| template<typename T > | |
| using | lvr2::Vector4 = Eigen::Matrix< T, 4, 1 > | 
| Eigen 4D vector.  More... | |
| using | lvr2::Vector4d = Eigen::Vector4d | 
| Eigen 4D vector, double precision.  More... | |
| using | lvr2::Vector4f = Eigen::Vector4f | 
| Eigen 4D vector, single precision.  More... | |
| using | lvr2::Vector6d = Eigen::Matrix< double, 6, 1 > | 
| 6D vector double precision  More... | |
| using | lvr2::Vector6f = Eigen::Matrix< float, 6, 1 > | 
| 6D vector, single precision  More... | |
| Functions | |
| template<typename T > | |
| Vector3< T > | lvr2::multiply (const Transform< T > &transform, const Vector3< T > &p) | 
| template<typename T > | |
| lvr2::Vector3< T > | operator* (const lvr2::Transform< T > &transform, const lvr2::Vector3< T > &p) | 
Copyright (c) 2018, University Osnabrück All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL University Osnabrück BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Definition in file MatrixTypes.hpp.
| lvr2::Vector3<T> operator* | ( | const lvr2::Transform< T > & | transform, | 
| const lvr2::Vector3< T > & | p | ||
| ) | 
Definition at line 180 of file MatrixTypes.hpp.