#include <Eigen/Geometry>
#include "pcl/common/transform.hpp"
Go to the source code of this file.
Namespaces | |
namespace | pcl |
Functions | |
void | pcl::getEulerAngles (const Eigen::Affine3f &t, float &roll, float &pitch, float &yaw) |
Extract the Euler angles (XYZ-convention) from the given transformation. | |
Eigen::Affine3f | pcl::getInverse (const Eigen::Affine3f &transformation) |
Get the inverse of an Eigen::Affine3f object. | |
void | pcl::getInverse (const Eigen::Affine3f &transformation, Eigen::Affine3f &inverse_transformation) |
Get the inverse of an Eigen::Affine3f object. | |
Eigen::Affine3f | pcl::getRotation (const Eigen::Affine3f &transformation) |
Get only the rotation part of the transformation. | |
Eigen::Affine3f | pcl::getTransformation (float x, float y, float z, float roll, float pitch, float yaw) |
Create a transformation from the given translation and Euler angles (XYZ-convention). | |
void | pcl::getTransformation (float x, float y, float z, float roll, float pitch, float yaw, Eigen::Affine3f &t) |
Create a transformation from the given translation and Euler angles (XYZ-convention). | |
Eigen::Affine3f | pcl::getTransformationFromTwoUnitVectors (const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis) |
void | pcl::getTransformationFromTwoUnitVectors (const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis, Eigen::Affine3f &transformation) |
void | pcl::getTransformationFromTwoUnitVectorsAndOrigin (const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis, const Eigen::Vector3f &origin, Eigen::Affine3f &transformation) |
Get the transformation that will translate orign to (0,0,0) and rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis). | |
template<typename PointCloudType > | |
void | pcl::getTransformedPointCloud (const PointCloudType &input, const Eigen::Affine3f &transformation, PointCloudType &output) |
Transform each point in the given point cloud according to the given transformation. | |
Eigen::Affine3f | pcl::getTransFromUnitVectorsXY (const Eigen::Vector3f &x_axis, const Eigen::Vector3f &y_direction) |
Get the unique 3D rotation that will rotate x_axis into (1,0,0) and y_direction into a vector with z=0 (or into (0,1,0) should y_direction be orthogonal to z_axis). | |
void | pcl::getTransFromUnitVectorsXY (const Eigen::Vector3f &x_axis, const Eigen::Vector3f &y_direction, Eigen::Affine3f &transformation) |
Get the unique 3D rotation that will rotate x_axis into (1,0,0) and y_direction into a vector with z=0 (or into (0,1,0) should y_direction be orthogonal to z_axis). | |
Eigen::Affine3f | pcl::getTransFromUnitVectorsZY (const Eigen::Vector3f &z_axis, const Eigen::Vector3f &y_direction) |
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis). | |
void | pcl::getTransFromUnitVectorsZY (const Eigen::Vector3f &z_axis, const Eigen::Vector3f &y_direction, Eigen::Affine3f &transformation) |
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis). | |
Eigen::Vector3f | pcl::getTranslation (const Eigen::Affine3f &transformation) |
Get only the translation part of the transformation. | |
void | pcl::getTranslationAndEulerAngles (const Eigen::Affine3f &t, float &x, float &y, float &z, float &roll, float &pitch, float &yaw) |
template<typename Derived > | |
void | pcl::loadBinary (Eigen::MatrixBase< Derived > &matrix, std::istream &file) |
Read a matrix from an input stream. | |
std::ostream & | pcl::operator<< (std::ostream &os, const Eigen::Affine3f &m) |
Output operator for Tranform3f. | |
template<typename Derived > | |
void | pcl::saveBinary (const Eigen::MatrixBase< Derived > &matrix, std::ostream &file) |
Write a matrix to an output stream. | |
template<typename PointType > | |
PointType | pcl::transformXYZ (const Eigen::Affine3f &transformation, const PointType &point) |
Transform a point with members x,y,z. |