00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef PCL_TRANSFORM_H_
00037 #define PCL_TRANSFORM_H_
00038
00039 #include <Eigen/Geometry>
00040
00041
00042
00043
00044
00045 namespace pcl
00046 {
00053 inline void
00054 getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, const Eigen::Vector3f& y_direction,
00055 Eigen::Affine3f& transformation);
00056
00063 inline Eigen::Affine3f
00064 getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, const Eigen::Vector3f& y_direction);
00065
00072 inline void
00073 getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, const Eigen::Vector3f& y_direction,
00074 Eigen::Affine3f& transformation);
00075
00082 inline Eigen::Affine3f
00083 getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, const Eigen::Vector3f& y_direction);
00084
00086 inline void
00087 getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis,
00088 Eigen::Affine3f& transformation);
00089
00091 inline Eigen::Affine3f
00092 getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis);
00093
00101 inline void
00102 getTransformationFromTwoUnitVectorsAndOrigin (const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis,
00103 const Eigen::Vector3f& origin, Eigen::Affine3f& transformation);
00104
00109 inline std::ostream&
00110 operator<< (std::ostream& os, const Eigen::Affine3f& m)
00111 {
00112 os << "{(" << m (0,0) << "," <<m (0,1) << "," << m (0,2) << "," << m (0,3)
00113 << ")(" << m (1,0) << "," <<m (1,1) << "," << m (1,2) << "," << m (1,3)
00114 << ")(" << m (2,0) << "," <<m (2,1) << "," << m (2,2) << "," << m (2,3)
00115 << ")(" << m (3,0) << "," <<m (3,1) << "," << m (3,2) << "," << m (3,3) << ")}";
00116 return (os);
00117 }
00118
00123 inline Eigen::Affine3f
00124 getRotation (const Eigen::Affine3f& transformation);
00125
00130 inline Eigen::Vector3f
00131 getTranslation (const Eigen::Affine3f& transformation);
00132
00137 inline void
00138 getInverse (const Eigen::Affine3f& transformation, Eigen::Affine3f& inverse_transformation);
00139
00144 inline Eigen::Affine3f getInverse (const Eigen::Affine3f& transformation);
00145
00151 template <typename PointType> inline PointType
00152 transformXYZ (const Eigen::Affine3f& transformation, const PointType& point);
00153
00159 template <typename PointCloudType> inline void
00160 getTransformedPointCloud (const PointCloudType& input, const Eigen::Affine3f& transformation,
00161 PointCloudType& output);
00162
00169 inline void
00170 getEulerAngles (const Eigen::Affine3f& t, float& roll, float& pitch, float& yaw);
00171
00181 inline void
00182 getTranslationAndEulerAngles (const Eigen::Affine3f& t, float& x, float& y, float& z,
00183 float& roll, float& pitch, float& yaw);
00184
00194 inline void
00195 getTransformation (float x, float y, float z, float roll, float pitch, float yaw, Eigen::Affine3f& t);
00196
00206 inline Eigen::Affine3f
00207 getTransformation (float x, float y, float z, float roll, float pitch, float yaw);
00208
00213 template <typename Derived> void
00214 saveBinary (const Eigen::MatrixBase<Derived>& matrix, std::ostream& file);
00215
00220 template <typename Derived> void
00221 loadBinary (Eigen::MatrixBase<Derived>& matrix, std::istream& file);
00222
00223 }
00224
00225 #include "pcl/common/transform.hpp"
00226
00227 #endif //#ifndef PCL_NORMS_H_