21 #ifndef ROBOT_CALIBRATION_EIGEN_GEOMETRY_H 22 #define ROBOT_CALIBRATION_EIGEN_GEOMETRY_H 26 #include <Eigen/Dense> 27 #include <geometry_msgs/PointStamped.h> 35 inline Eigen::MatrixXd
getMatrix(
const std::vector<geometry_msgs::PointStamped>& points)
37 Eigen::MatrixXd matrix(3, points.size());
38 for (
size_t i = 0; i < points.size(); ++i)
40 matrix(0, i) = points[i].point.x;
41 matrix(1, i) = points[i].point.y;
42 matrix(2, i) = points[i].point.z;
52 return Eigen::Vector3d(points.row(0).mean(), points.row(1).mean(), points.row(2).mean());
64 inline bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d& normal,
double& d)
70 points.row(0).array() -= centroid(0);
71 points.row(1).array() -= centroid(1);
72 points.row(2).array() -= centroid(2);
75 auto svd = points.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV);
76 normal = svd.matrixU().rightCols<1>();
79 d = -(normal(0) * centroid(0) + normal(1) * centroid(1) + normal(2) * centroid(2));
93 #endif // ROBOT_CALIBRATION_EIGEN_GEOMETRY_H Eigen::Vector3d getCentroid(Eigen::MatrixXd points)
Get the centroid of a point cloud.
Calibration code lives under this namespace.
Eigen::MatrixXd getMatrix(const std::vector< geometry_msgs::PointStamped > &points)
Get an Eigen::MatrixXd from a vector of PointStamped.
bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d &normal, double &d)
Find the plane parameters for a point cloud.