#include <sensor_msgs/PointCloud.h>#include <geometry_msgs/Point32.h>#include <vector>#include <Eigen/Core>#include <Eigen/LU>

Go to the source code of this file.
Namespaces | |
| namespace | cloud_geometry |
| namespace | cloud_geometry::transforms |
Functions | |
| void | cloud_geometry::transforms::convertAxisAngleToRotationMatrix (const geometry_msgs::Point32 &axis, double angle, Eigen::Matrix3d &rotation) |
| Convert an axis-angle representation to a 3x3 rotation matrix. | |
| void | cloud_geometry::transforms::getInverseTransformation (const Eigen::Matrix4d &transformation, Eigen::Matrix4d &transformation_inverse) |
| Obtain the inverse of a 4x4 rigid transformation matrix. | |
| void | cloud_geometry::transforms::getPlaneToPlaneTransformation (const std::vector< double > &plane_a, const std::vector< double > &plane_b, float tx, float ty, float tz, Eigen::Matrix4d &transformation) |
| Obtain a 4x4 rigid transformation matrix (with translation) | |
| void | cloud_geometry::transforms::getPlaneToPlaneTransformation (const std::vector< double > &plane_a, const geometry_msgs::Point32 &plane_b, float tx, float ty, float tz, Eigen::Matrix4d &transformation) |
| Obtain a 4x4 rigid transformation matrix (with translation) | |
| bool | cloud_geometry::transforms::getPointsRigidTransformation (const sensor_msgs::PointCloud &pc_a, const sensor_msgs::PointCloud &pc_b, Eigen::Matrix4d &transformation) |
| Computes the rigid transformation between two point clouds. | |
| bool | cloud_geometry::transforms::getPointsRigidTransformation (const sensor_msgs::PointCloud &pc_a, const std::vector< int > &indices_a, const sensor_msgs::PointCloud &pc_b, const std::vector< int > &indices_b, Eigen::Matrix4d &transformation) |
| Computes the rigid transformation between two point clouds. | |
| void | cloud_geometry::transforms::transformPoint (const geometry_msgs::Point32 &point_in, geometry_msgs::Point32 &point_out, const Eigen::Matrix4d &transformation) |
| Transform a 3D point using a given 4x4 rigid transformation. | |
| void | cloud_geometry::transforms::transformPoints (const std::vector< geometry_msgs::Point32 > &points_in, std::vector< geometry_msgs::Point32 > &points_out, const Eigen::Matrix4d &transformation) |
| Transform a set of 3D points using a given 4x4 rigid transformation. | |