10 #ifndef EIGEN_COMPANION_H 11 #define EIGEN_COMPANION_H 21 #ifndef EIGEN_PARSED_BY_DOXYGEN 32 template<
typename _Scalar,
int _Deg >
59 if( m_bl_diag.rows() >
col )
61 if( 0 < row ){
return m_bl_diag[
col]; }
64 else{
return m_monic[
row]; }
68 template<
typename VectorType>
71 const Index deg = poly.size()-1;
72 m_monic = -poly.head(deg)/poly[deg];
73 m_bl_diag.setOnes(deg-1);
76 template<
typename VectorType>
78 setPolynomial( poly ); }
83 const Index deg = m_monic.size();
84 const Index deg_1 = deg-1;
85 DenseCompanionMatrixType companMat(deg,deg);
87 ( LeftBlock(deg,deg_1)
88 << LeftBlockFirstRow::Zero(1,deg_1),
89 BottomLeftBlock::Identity(deg-1,deg-1)*m_bl_diag.asDiagonal() ).finished()
103 bool balanced( RealScalar colNorm, RealScalar rowNorm,
104 bool& isBalanced, RealScalar& colB, RealScalar& rowB );
112 bool balancedR( RealScalar colNorm, RealScalar rowNorm,
113 bool& isBalanced, RealScalar& colB, RealScalar& rowB );
133 template<
typename _Scalar,
int _Deg >
152 rowB = rowNorm / radix;
166 scout = colNorm * (colB / radix) * colB;
167 while (scout >= rowNorm)
174 if ((rowNorm + radix * scout) <
RealScalar(0.95) * s * colB)
187 template<
typename _Scalar,
int _Deg >
202 rowB =
sqrt( colNorm/rowNorm );
214 template<
typename _Scalar,
int _Deg >
219 const Index deg = m_monic.size();
220 const Index deg_1 = deg-1;
222 bool hasConverged=
false;
223 while( !hasConverged )
231 colNorm =
abs(m_bl_diag[0]);
232 rowNorm =
abs(m_monic[0]);
235 if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )
237 m_bl_diag[0] *= colB;
246 colNorm =
abs(m_bl_diag[
i]);
249 rowNorm =
abs(m_bl_diag[i-1]) +
abs(m_monic[i]);
252 if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )
254 m_bl_diag[
i] *= colB;
255 m_bl_diag[i-1] *= rowB;
262 const Index ebl = m_bl_diag.size()-1;
264 colNorm = headMonic.array().abs().sum();
265 rowNorm =
abs( m_bl_diag[ebl] );
268 if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )
271 m_bl_diag[ebl] *= rowB;
280 #endif // EIGEN_COMPANION_H NumTraits< Scalar >::Real RealScalar
#define EIGEN_STRONG_INLINE
Matrix< Scalar, 1, Deg_1 > LeftBlockFirstRow
bool balancedR(RealScalar colNorm, RealScalar rowNorm, bool &isBalanced, RealScalar &colB, RealScalar &rowB)
BottomLeftDiagonal m_bl_diag
Namespace containing all symbols from the Eigen library.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
DenseCompanionMatrixType denseMatrix() const
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar, Size)
void setPolynomial(const VectorType &poly)
Matrix< Scalar, Deg_1, 1 > BottomLeftDiagonal
Expression of a fixed-size or dynamic-size sub-vector.
EIGEN_STRONG_INLINE const _Scalar operator()(Index row, Index col) const
bool balanced(RealScalar colNorm, RealScalar rowNorm, bool &isBalanced, RealScalar &colB, RealScalar &rowB)
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool() isfinite(const Eigen::bfloat16 &h)
EIGEN_DEVICE_FUNC const Scalar & q
Matrix< Scalar, Deg, 1 > RightColumn
NumTraits< Scalar >::Real RealScalar
companion(const VectorType &poly)
EIGEN_DEFAULT_DENSE_INDEX_TYPE DenseIndex
Matrix< Scalar, Deg_1, Deg_1 > BottomLeftBlock
Jet< T, N > sqrt(const Jet< T, N > &f)
EIGEN_DEVICE_FUNC bool isApprox(const Scalar &x, const Scalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
Matrix< Scalar, Deg, Deg > DenseCompanionMatrixType
Matrix< Scalar, _Deg, Deg_1 > LeftBlock