Functions | |
void | convertAxisAngleToRotationMatrix (const geometry_msgs::Point32 &axis, double angle, Eigen::Matrix3d &rotation) |
Convert an axis-angle representation to a 3x3 rotation matrix. | |
void | getInverseTransformation (const Eigen::Matrix4d &transformation, Eigen::Matrix4d &transformation_inverse) |
Obtain the inverse of a 4x4 rigid transformation matrix. | |
void | 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 | 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 | 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 | 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 | 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 | 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. |
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.
axis | the axis |
angle | the angle |
rotation | the resultant rotation |
Definition at line 307 of file transforms.cpp.
void cloud_geometry::transforms::getInverseTransformation | ( | const Eigen::Matrix4d & | transformation, |
Eigen::Matrix4d & | transformation_inverse | ||
) | [inline] |
Obtain the inverse of a 4x4 rigid transformation matrix.
transformation | the input transformation |
transformation_inverse | the output transformation (the inverse of transformation) |
Definition at line 123 of file transforms.h.
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)
plane_a | the normalized coefficients of the first plane |
plane_b | the normalized coefficients of the second plane |
tx | the desired translation on x-axis |
ty | the desired translation on y-axis |
tz | the desired translation on z-axis |
transformation | the resultant transformation matrix |
Definition at line 226 of file transforms.cpp.
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)
plane_a | the normalized coefficients of the first plane |
plane_b | the normalized coefficients of the second plane |
tx | the desired translation on x-axis |
ty | the desired translation on y-axis |
tz | the desired translation on z-axis |
transformation | the resultant transformation matrix |
Definition at line 267 of file transforms.cpp.
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.
Computes the optimal transformation between two sets of point clouds (in a least square sense), using the algorithm of: Arun, Huanng and Blostein - Least-Square Fitting of Two Point Sets
pc_a | first point cloud |
pc_b | second point cloud |
transformation | the computed transformation between the two point clouds |
See header file
Definition at line 49 of file transforms.cpp.
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.
Computes the optimal transformation between two sets of point clouds (in a least square sense), using the algorithm of: Arun, Huanng and Blostein - Least-Square Fitting of Two Point Sets
pc_a | first point cloud |
indices_a | indices of points from the first point cloud to be used |
pc_b | second point cloud |
indices_b | indices of points from the first point cloud to be used |
transformation | the computed transformation between the two point clouds |
See header file
Definition at line 129 of file transforms.cpp.
void cloud_geometry::transforms::transformPoint | ( | const geometry_msgs::Point32 & | point_in, |
geometry_msgs::Point32 & | point_out, | ||
const Eigen::Matrix4d & | transformation | ||
) | [inline] |
Transform a 3D point using a given 4x4 rigid transformation.
point_in | the input point |
point_out | the resultant transformed point |
transform | the 4x4 rigid transformation |
Definition at line 95 of file transforms.h.
void cloud_geometry::transforms::transformPoints | ( | const std::vector< geometry_msgs::Point32 > & | points_in, |
std::vector< geometry_msgs::Point32 > & | points_out, | ||
const Eigen::Matrix4d & | transformation | ||
) | [inline] |
Transform a set of 3D points using a given 4x4 rigid transformation.
points_in | the input points |
points_out | the resultant transformed points |
transform | the 4x4 rigid transformation |
Definition at line 109 of file transforms.h.