eigen_geometry.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015-2017 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Michael Ferguson
20 
21 #ifndef ROBOT_CALIBRATION_EIGEN_GEOMETRY_H
22 #define ROBOT_CALIBRATION_EIGEN_GEOMETRY_H
23 
24 #include <vector>
25 #include <Eigen/Core>
26 #include <Eigen/Dense>
27 #include <geometry_msgs/PointStamped.h>
28 
29 namespace robot_calibration
30 {
31 
35 inline Eigen::MatrixXd getMatrix(const std::vector<geometry_msgs::PointStamped>& points)
36 {
37  Eigen::MatrixXd matrix(3, points.size());
38  for (size_t i = 0; i < points.size(); ++i)
39  {
40  matrix(0, i) = points[i].point.x;
41  matrix(1, i) = points[i].point.y;
42  matrix(2, i) = points[i].point.z;
43  }
44  return matrix;
45 }
46 
50 inline Eigen::Vector3d getCentroid(Eigen::MatrixXd points)
51 {
52  return Eigen::Vector3d(points.row(0).mean(), points.row(1).mean(), points.row(2).mean());
53 }
54 
64 inline bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d& normal, double& d)
65 {
66  // Find centroid
67  Eigen::Vector3d centroid = getCentroid(points);
68 
69  // Center the cloud
70  points.row(0).array() -= centroid(0);
71  points.row(1).array() -= centroid(1);
72  points.row(2).array() -= centroid(2);
73 
74  // Find the plane
75  auto svd = points.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV);
76  normal = svd.matrixU().rightCols<1>();
77 
78  // Get the rest of plane equation
79  d = -(normal(0) * centroid(0) + normal(1) * centroid(1) + normal(2) * centroid(2));
80 
81  if (d < 0)
82  {
83  // Invert the normal vector so that d is always positive
84  d *= -1;
85  normal *= -1;
86  }
87 
88  return true;
89 }
90 
91 } // namespace robot_calibration
92 
93 #endif // ROBOT_CALIBRATION_EIGEN_GEOMETRY_H
robot_calibration::getMatrix
Eigen::MatrixXd getMatrix(const std::vector< geometry_msgs::PointStamped > &points)
Get an Eigen::MatrixXd from a vector of PointStamped.
Definition: eigen_geometry.h:35
d
d
robot_calibration::getCentroid
Eigen::Vector3d getCentroid(Eigen::MatrixXd points)
Get the centroid of a point cloud.
Definition: eigen_geometry.h:50
robot_calibration::getPlane
bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d &normal, double &d)
Find the plane parameters for a point cloud.
Definition: eigen_geometry.h:64
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01