Go to the documentation of this file.
11 #ifndef SPECTRA_UPPER_HESSENBERG_SCHUR_H
12 #define SPECTRA_UPPER_HESSENBERG_SCHUR_H
15 #include <Eigen/Jacobi>
16 #include <Eigen/Householder>
19 #include "../Util/TypeTraits.h"
23 template <
typename Scalar =
double>
46 norm +=
x.col(
j).segment(0, (
std::min)(
n,
j + 2)).cwiseAbs().sum();
60 s = Eigen::numext::maxi<Scalar>(
s * eps, near_0);
87 m_T.rightCols(
m_n - iu + 1).applyOnTheLeft(iu - 1, iu,
rot.adjoint());
88 m_T.topRows(iu + 1).applyOnTheRight(iu - 1, iu,
rot);
90 m_U.applyOnTheRight(iu - 1, iu,
rot);
109 ex_shift += shift_info.
coeff(0);
126 if (shift_info.
coeff(1) < shift_info.
coeff(0))
145 for (im = iu - 2; im >= il; --im)
151 v.coeffRef(1) =
m_T.
coeff(im + 1, im + 1) - Tmm - r -
s;
152 v.coeffRef(2) =
m_T.
coeff(im + 2, im + 1);
157 if (
abs(lhs) < eps * rhs)
167 const Scalar*
const x_end =
x + ncol * stride;
168 for (;
x < x_end;
x += stride)
207 constexpr
unsigned char Peeling = 2;
208 constexpr
unsigned char Increment = Peeling * PacketSize;
222 const Packet vtau = pset1<Packet>(tau);
223 const Packet vv1 = pset1<Packet>(
v1);
224 const Packet vv2 = pset1<Packet>(
v2);
228 const Index aligned_end = nrow - (nrow & (PacketSize - 1));
229 const Index peeling_end = nrow - (nrow & (Increment - 1));
230 for (
Index i = 0;
i < peeling_end;
i += Increment)
232 Packet vx01 = ploadu<Packet>(px0);
233 Packet vx02 = ploadu<Packet>(px0 + PacketSize);
234 Packet vx11 = ploadu<Packet>(px1);
235 Packet vx12 = ploadu<Packet>(px1 + PacketSize);
236 Packet vx21 = ploadu<Packet>(px2);
237 Packet vx22 = ploadu<Packet>(px2 + PacketSize);
254 if (aligned_end != peeling_end)
256 px0 =
x0 + peeling_end;
257 px1 =
x1 + peeling_end;
258 px2 =
x2 + peeling_end;
260 Packet x0_p = ploadu<Packet>(px0);
261 Packet x1_p = ploadu<Packet>(px1);
262 Packet x2_p = ploadu<Packet>(px2);
271 for (
Index i = aligned_end;
i < nrow;
i++)
285 for (
Index k = im; k <= iu - 2; ++k)
287 const bool first_iter = (k == im);
290 v = first_householder_vec;
292 v =
m_T.template block<3, 1>(k, k - 1);
296 v.makeHouseholder(ess, tau,
beta);
300 if (first_iter && k > il)
302 else if (!first_iter)
323 m_T.rightCols(
m_n - iu + 1).applyOnTheLeft(iu - 1, iu,
rot.adjoint());
324 m_T.topRows(iu + 1).applyOnTheRight(iu - 1, iu,
rot);
325 m_U.applyOnTheRight(iu - 1, iu,
rot);
329 for (
Index i = im + 2;
i <= iu; ++
i)
353 if (
mat.rows() !=
mat.cols())
354 throw std::invalid_argument(
"UpperHessenbergSchur: matrix must be square");
359 constexpr
Index max_iter_per_row = 40;
360 const Index max_iter =
m_n * max_iter_per_row;
371 Index total_iter = 0;
394 else if (il == iu - 1)
402 Vector3s first_householder_vec = Vector3s::Zero(), shift_info;
406 if (total_iter > max_iter)
415 if (total_iter > max_iter)
416 throw std::runtime_error(
"UpperHessenbergSchur: Schur decomposition failed");
424 throw std::logic_error(
"UpperHessenbergSchur: need to call compute() first");
432 throw std::logic_error(
"UpperHessenbergSchur: need to call compute() first");
450 #endif // SPECTRA_UPPER_HESSENBERG_SCHUR_H
static void apply_householder_left(const Vector2s &ess, const Scalar &tau, Scalar *x, Index ncol, Index stride)
EIGEN_DEVICE_FUNC void pstoreu(Scalar *to, const Packet &from)
const Matrix & matrix_T() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(DenseBase< OtherDerived > &other)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Index find_small_subdiag(Index iu, const Scalar &near_0) const
void compute_shift(Index iu, Index iter, Scalar &ex_shift, Vector3s &shift_info)
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
Rotation given by a cosine-sine pair.
double beta(double a, double b)
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
void init_francis_qr_step(Index il, Index iu, const Vector3s &shift_info, Index &im, Vector3s &first_householder_vec) const
EIGEN_DEVICE_FUNC Derived & setConstant(Index size, const Scalar &val)
static void apply_householder_right(const Vector2s &ess, const Scalar &tau, Scalar *x, Index nrow, Index stride)
EIGEN_DEVICE_FUNC const Scalar & q
void compute(ConstGenericMatrix &mat)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
EIGEN_DEVICE_FUNC Packet psub(const Packet &a, const Packet &b)
static Scalar upper_hessenberg_l1_norm(ConstGenericMatrix &x)
void swap_U(Matrix &other)
static void apply_householder_right_simd(const Vector2s &ess, const Scalar &tau, Scalar *x, Index nrow, Index stride)
void perform_francis_qr_step(Index il, Index im, Index iu, const Vector3s &first_householder_vec, const Scalar &near_0)
A matrix or vector expression mapping an existing expression.
const Matrix & matrix_U() const
EIGEN_DEVICE_FUNC Packet pmul(const Packet &a, const Packet &b)
void swap_T(Matrix &other)
iterator iter(handle obj)
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar & coeff(Index rowId, Index colId) const
Array< int, Dynamic, 1 > v
void split_off_two_rows(Index iu, const Scalar &ex_shift)
EIGEN_DEVICE_FUNC Packet padd(const Packet &a, const Packet &b)
EIGEN_DEVICE_FUNC Packet pset1(const typename unpacket_traits< Packet >::type &a)
EIGEN_DEVICE_FUNC Packet ploadu(const typename unpacket_traits< Packet >::type *from)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Jet< T, N > sqrt(const Jet< T, N > &f)
UpperHessenbergSchur(ConstGenericMatrix &mat)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
gtsam
Author(s):
autogenerated on Wed Apr 16 2025 03:10:02