13 #include <Eigen/Geometry>
18 using namespace Eigen;
30 bool is_unitary =
false;
32 while (!is_unitary && max_tries > 0)
41 for (
int prevCol = 0; prevCol <
col; ++prevCol)
44 colVec -= colVec.dot(prevColVec)*prevColVec;
46 Q.col(
col) = colVec.normalized();
54 for (
int prevRow = 0; prevRow <
row; ++prevRow)
57 rowVec -= rowVec.dot(prevRowVec)*prevRowVec;
59 Q.row(
row) = rowVec.normalized();
63 is_unitary =
Q.isUnitary();
68 eigen_assert(
false &&
"randMatrixUnitary: Could not construct unitary matrix!");
90 template <
typename MatrixType>
100 const Scalar c =
abs(internal::random<Scalar>());
102 MatrixX
R = randMatrixSpecialUnitary<Scalar>(dim);
105 MatrixX cR_t = MatrixX::Identity(dim+1,dim+1);
106 cR_t.block(0,0,dim,dim) =
c*
R;
107 cR_t.block(0,dim,dim,1) =
t;
109 MatrixX src = MatrixX::Random(dim+1, num_elements);
112 MatrixX dst = cR_t*src;
114 MatrixX cR_t_umeyama =
umeyama(src.block(0,0,dim,num_elements), dst.block(0,0,dim,num_elements));
116 const Scalar error = ( cR_t_umeyama*src - dst ).norm() / dst.norm();
120 template<
typename Scalar,
int Dimension>
129 const int dim = Dimension;
134 const Scalar c = internal::random<Scalar>(0.5, 2.0);
136 FixedMatrix
R = randMatrixSpecialUnitary<Scalar>(dim);
137 FixedVector
t =
Scalar(32)*FixedVector::Random(dim,1);
139 HomMatrix cR_t = HomMatrix::Identity(dim+1,dim+1);
140 cR_t.block(0,0,dim,dim) =
c*
R;
141 cR_t.block(0,dim,dim,1) =
t;
143 MatrixX src = MatrixX::Random(dim+1, num_elements);
146 MatrixX dst = cR_t*src;
151 HomMatrix cR_t_umeyama =
umeyama(src_block, dst_block);
153 const Scalar error = ( cR_t_umeyama*src - dst ).squaredNorm();
162 const int num_elements = internal::random<int>(40,500);
165 for (
int dim=2; dim<8; ++dim)