Functions | |
| double | alignICP (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform, size_t max_iterations=10, double min_delta_rmsd=0.000001) |
| Perform Iterative Closest Point (ICP) algorithm to align two point clouds in a two dimensional plane. More... | |
| bool | alignPCA (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform) |
| Perform PCA algorithm to align two point clouds in a two dimensional plane. More... | |
| bool | alignSVD (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform) |
| Perform SVD optimization to align two point clouds in a two dimensional plane. More... | |
| bool | computeCorrespondences (const std::vector< geometry_msgs::Point > &source, const std::vector< geometry_msgs::Point > &target, std::vector< geometry_msgs::Point > &correspondences) |
| geometry_msgs::Point | getCentroid (const std::vector< geometry_msgs::Point > points) |
| Get the centroid of a set of points. More... | |
| double | getRMSD (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target) |
| double | thetaFromQuaternion (const geometry_msgs::Quaternion &q) |
| Get the 2d rotation from a quaternion. More... | |
| std::vector< geometry_msgs::Point > | transform (const std::vector< geometry_msgs::Point > &points, double x, double y, double theta) |
| Transform a vector of points in 2d. More... | |
| double icp_2d::alignICP | ( | const std::vector< geometry_msgs::Point > | source, |
| const std::vector< geometry_msgs::Point > | target, | ||
| geometry_msgs::Transform & | transform, | ||
| size_t | max_iterations = 10, |
||
| double | min_delta_rmsd = 0.000001 |
||
| ) |
Perform Iterative Closest Point (ICP) algorithm to align two point clouds in a two dimensional plane.
| source | The cloud to be aligned with target. |
| target | The cloud to be aligned to. |
| transform | The transformation to align source with target. |
Definition at line 289 of file icp_2d.cpp.
| bool icp_2d::alignPCA | ( | const std::vector< geometry_msgs::Point > | source, |
| const std::vector< geometry_msgs::Point > | target, | ||
| geometry_msgs::Transform & | transform | ||
| ) |
Perform PCA algorithm to align two point clouds in a two dimensional plane.
| source | The cloud to be aligned with target. |
| target | The cloud to be aligned to. |
| transform | The transformation to align source with target. |
Definition at line 119 of file icp_2d.cpp.
| bool icp_2d::alignSVD | ( | const std::vector< geometry_msgs::Point > | source, |
| const std::vector< geometry_msgs::Point > | target, | ||
| geometry_msgs::Transform & | transform | ||
| ) |
Perform SVD optimization to align two point clouds in a two dimensional plane.
| source | The cloud to be aligned with target. |
| target | The cloud to be aligned to. |
| transform | The transformation to align source with target. |
Definition at line 197 of file icp_2d.cpp.
| bool icp_2d::computeCorrespondences | ( | const std::vector< geometry_msgs::Point > & | source, |
| const std::vector< geometry_msgs::Point > & | target, | ||
| std::vector< geometry_msgs::Point > & | correspondences | ||
| ) |
Definition at line 82 of file icp_2d.cpp.
| geometry_msgs::Point icp_2d::getCentroid | ( | const std::vector< geometry_msgs::Point > | points | ) |
Get the centroid of a set of points.
| points | The points to find centroid of. |
Definition at line 66 of file icp_2d.cpp.
| double icp_2d::getRMSD | ( | const std::vector< geometry_msgs::Point > | source, |
| const std::vector< geometry_msgs::Point > | target | ||
| ) |
Definition at line 262 of file icp_2d.cpp.
| double icp_2d::thetaFromQuaternion | ( | const geometry_msgs::Quaternion & | q | ) |
Get the 2d rotation from a quaternion.
| q | The quaternion to convert. |
Note: will throw if q.x or q.y is not equal to zero
Definition at line 28 of file icp_2d.cpp.
| std::vector< geometry_msgs::Point > icp_2d::transform | ( | const std::vector< geometry_msgs::Point > & | points, |
| double | x, | ||
| double | y, | ||
| double | theta | ||
| ) |
Transform a vector of points in 2d.
| points | The points to transform. |
| x | The x offset to transform, in the current frame of points. |
| y | The y offset to transform, in the current frame of points. |
| theta | The rotation, in the current frame of points. |
Definition at line 41 of file icp_2d.cpp.