schkgg.c
Go to the documentation of this file.
00001 /* schkgg.f -- translated by f2c (version 20061008).
00002    You must link the resulting object file with libf2c:
00003         on Microsoft Windows system, link with libf2c.lib;
00004         on Linux or Unix systems, link with .../path/to/libf2c.a -lm
00005         or, if you install libf2c.a in a standard place, with -lf2c -lm
00006         -- in that order, at the end of the command line, as in
00007                 cc *.o -lf2c -lm
00008         Source for libf2c is in /netlib/f2c/libf2c.zip, e.g.,
00009 
00010                 http://www.netlib.org/f2c/libf2c.zip
00011 */
00012 
00013 #include "f2c.h"
00014 #include "blaswrap.h"
00015 
00016 /* Table of constant values */
00017 
00018 static real c_b13 = 0.f;
00019 static integer c__2 = 2;
00020 static real c_b19 = 1.f;
00021 static integer c__3 = 3;
00022 static integer c__1 = 1;
00023 static integer c__4 = 4;
00024 static logical c_true = TRUE_;
00025 static logical c_false = FALSE_;
00026 
00027 /* Subroutine */ int schkgg_(integer *nsizes, integer *nn, integer *ntypes, 
00028         logical *dotype, integer *iseed, real *thresh, logical *tstdif, real *
00029         thrshn, integer *nounit, real *a, integer *lda, real *b, real *h__, 
00030         real *t, real *s1, real *s2, real *p1, real *p2, real *u, integer *
00031         ldu, real *v, real *q, real *z__, real *alphr1, real *alphi1, real *
00032         beta1, real *alphr3, real *alphi3, real *beta3, real *evectl, real *
00033         evectr, real *work, integer *lwork, logical *llwork, real *result, 
00034         integer *info)
00035 {
00036     /* Initialized data */
00037 
00038     static integer kclass[26] = { 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,2,2,2,2,2,2,2,
00039             2,2,2,3 };
00040     static integer kbmagn[26] = { 1,1,1,1,1,1,1,1,3,2,3,2,2,3,1,1,1,1,1,1,1,3,
00041             2,3,2,1 };
00042     static integer ktrian[26] = { 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,
00043             1,1,1,1 };
00044     static integer iasign[26] = { 0,0,0,0,0,0,2,0,2,2,0,0,2,2,2,0,2,0,0,0,2,2,
00045             2,2,2,0 };
00046     static integer ibsign[26] = { 0,0,0,0,0,0,0,2,0,0,2,2,0,0,2,0,2,0,0,0,0,0,
00047             0,0,0,0 };
00048     static integer kz1[6] = { 0,1,2,1,3,3 };
00049     static integer kz2[6] = { 0,0,1,2,1,1 };
00050     static integer kadd[6] = { 0,0,0,0,3,2 };
00051     static integer katype[26] = { 0,1,0,1,2,3,4,1,4,4,1,1,4,4,4,2,4,5,8,7,9,4,
00052             4,4,4,0 };
00053     static integer kbtype[26] = { 0,0,1,1,2,-3,1,4,1,1,4,4,1,1,-4,2,-4,8,8,8,
00054             8,8,8,8,8,0 };
00055     static integer kazero[26] = { 1,1,1,1,1,1,2,1,2,2,1,1,2,2,3,1,3,5,5,5,5,3,
00056             3,3,3,1 };
00057     static integer kbzero[26] = { 1,1,1,1,1,1,1,2,1,1,2,2,1,1,4,1,4,6,6,6,6,4,
00058             4,4,4,1 };
00059     static integer kamagn[26] = { 1,1,1,1,1,1,1,1,2,3,2,3,2,3,1,1,1,1,1,1,1,2,
00060             3,3,2,1 };
00061 
00062     /* Format strings */
00063     static char fmt_9999[] = "(\002 SCHKGG: \002,a,\002 returned INFO=\002,i"
00064             "6,\002.\002,/9x,\002N=\002,i6,\002, JTYPE=\002,i6,\002, ISEED="
00065             "(\002,3(i5,\002,\002),i5,\002)\002)";
00066     static char fmt_9998[] = "(\002 SCHKGG: \002,a,\002 Eigenvectors from"
00067             " \002,a,\002 incorrectly \002,\002normalized.\002,/\002 Bits of "
00068             "error=\002,0p,g10.3,\002,\002,9x,\002N=\002,i6,\002, JTYPE=\002,"
00069             "i6,\002, ISEED=(\002,3(i5,\002,\002),i5,\002)\002)";
00070     static char fmt_9997[] = "(/1x,a3,\002 -- Real Generalized eigenvalue pr"
00071             "oblem\002)";
00072     static char fmt_9996[] = "(\002 Matrix types (see SCHKGG for details):"
00073             " \002)";
00074     static char fmt_9995[] = "(\002 Special Matrices:\002,23x,\002(J'=transp"
00075             "osed Jordan block)\002,/\002   1=(0,0)  2=(I,0)  3=(0,I)  4=(I,I"
00076             ")  5=(J',J')  \002,\0026=(diag(J',I), diag(I,J'))\002,/\002 Diag"
00077             "onal Matrices:  ( \002,\002D=diag(0,1,2,...) )\002,/\002   7=(D,"
00078             "I)   9=(large*D, small*I\002,\002)  11=(large*I, small*D)  13=(l"
00079             "arge*D, large*I)\002,/\002   8=(I,D)  10=(small*D, large*I)  12="
00080             "(small*I, large*D) \002,\002 14=(small*D, small*I)\002,/\002  15"
00081             "=(D, reversed D)\002)";
00082     static char fmt_9994[] = "(\002 Matrices Rotated by Random \002,a,\002 M"
00083             "atrices U, V:\002,/\002  16=Transposed Jordan Blocks            "
00084             " 19=geometric \002,\002alpha, beta=0,1\002,/\002  17=arithm. alp"
00085             "ha&beta             \002,\002      20=arithmetic alpha, beta=0,"
00086             "1\002,/\002  18=clustered \002,\002alpha, beta=0,1            21"
00087             "=random alpha, beta=0,1\002,/\002 Large & Small Matrices:\002,"
00088             "/\002  22=(large, small)   \002,\00223=(small,large)    24=(smal"
00089             "l,small)    25=(large,large)\002,/\002  26=random O(1) matrices"
00090             ".\002)";
00091     static char fmt_9993[] = "(/\002 Tests performed:   (H is Hessenberg, S "
00092             "is Schur, B, \002,\002T, P are triangular,\002,/20x,\002U, V, Q,"
00093             " and Z are \002,a,\002, l and r are the\002,/20x,\002appropriate"
00094             " left and right eigenvectors, resp., a is\002,/20x,\002alpha, b "
00095             "is beta, and \002,a,\002 means \002,a,\002.)\002,/\002 1 = | A -"
00096             " U H V\002,a,\002 | / ( |A| n ulp )      2 = | B - U T V\002,a"
00097             ",\002 | / ( |B| n ulp )\002,/\002 3 = | I - UU\002,a,\002 | / ( "
00098             "n ulp )             4 = | I - VV\002,a,\002 | / ( n ulp )\002,"
00099             "/\002 5 = | H - Q S Z\002,a,\002 | / ( |H| n ulp )\002,6x,\0026 "
00100             "= | T - Q P Z\002,a,\002 | / ( |T| n ulp )\002,/\002 7 = | I - QQ"
00101             "\002,a,\002 | / ( n ulp )             8 = | I - ZZ\002,a,\002 | "
00102             "/ ( n ulp )\002,/\002 9 = max | ( b S - a P )\002,a,\002 l | / c"
00103             "onst.  10 = max | ( b H - a T )\002,a,\002 l | / const.\002,/"
00104             "\002 11= max | ( b S - a P ) r | / const.   12 = max | ( b H\002,"
00105             "\002 - a T ) r | / const.\002,/1x)";
00106     static char fmt_9992[] = "(\002 Matrix order=\002,i5,\002, type=\002,i2"
00107             ",\002, seed=\002,4(i4,\002,\002),\002 result \002,i2,\002 is\002"
00108             ",0p,f8.2)";
00109     static char fmt_9991[] = "(\002 Matrix order=\002,i5,\002, type=\002,i2"
00110             ",\002, seed=\002,4(i4,\002,\002),\002 result \002,i2,\002 is\002"
00111             ",1p,e10.3)";
00112 
00113     /* System generated locals */
00114     integer a_dim1, a_offset, b_dim1, b_offset, evectl_dim1, evectl_offset, 
00115             evectr_dim1, evectr_offset, h_dim1, h_offset, p1_dim1, p1_offset, 
00116             p2_dim1, p2_offset, q_dim1, q_offset, s1_dim1, s1_offset, s2_dim1,
00117              s2_offset, t_dim1, t_offset, u_dim1, u_offset, v_dim1, v_offset, 
00118             z_dim1, z_offset, i__1, i__2, i__3, i__4;
00119     real r__1, r__2, r__3, r__4;
00120 
00121     /* Builtin functions */
00122     double r_sign(real *, real *);
00123     integer s_wsfe(cilist *), do_fio(integer *, char *, ftnlen), e_wsfe(void);
00124 
00125     /* Local variables */
00126     integer j, n, i1, n1, jc, in, jr;
00127     real ulp;
00128     integer iadd, nmax;
00129     real temp1, temp2;
00130     logical badnn;
00131     real dumma[4];
00132     integer iinfo;
00133     real rmagn[4];
00134     extern /* Subroutine */ int sget51_(integer *, integer *, real *, integer 
00135             *, real *, integer *, real *, integer *, real *, integer *, real *
00136 , real *), sget52_(logical *, integer *, real *, integer *, real *
00137 , integer *, real *, integer *, real *, real *, real *, real *, 
00138             real *);
00139     real anorm, bnorm;
00140     integer nmats, jsize, nerrs, jtype, ntest;
00141     extern /* Subroutine */ int sgeqr2_(integer *, integer *, real *, integer 
00142             *, real *, real *, integer *), slatm4_(integer *, integer *, 
00143             integer *, integer *, integer *, real *, real *, real *, integer *
00144 , integer *, real *, integer *), sorm2r_(char *, char *, integer *
00145 , integer *, integer *, real *, integer *, real *, real *, 
00146             integer *, real *, integer *), slabad_(real *, 
00147             real *);
00148     extern doublereal slamch_(char *), slange_(char *, integer *, 
00149             integer *, real *, integer *, real *);
00150     real safmin;
00151     integer ioldsd[4];
00152     real safmax;
00153     extern /* Subroutine */ int sgghrd_(char *, char *, integer *, integer *, 
00154             integer *, real *, integer *, real *, integer *, real *, integer *
00155 , real *, integer *, integer *);
00156     extern doublereal slarnd_(integer *, integer *);
00157     extern /* Subroutine */ int slarfg_(integer *, real *, real *, integer *, 
00158             real *), xerbla_(char *, integer *), shgeqz_(char *, char 
00159             *, char *, integer *, integer *, integer *, real *, integer *, 
00160             real *, integer *, real *, real *, real *, real *, integer *, 
00161             real *, integer *, real *, integer *, integer *), slacpy_(char *, integer *, integer *, real *, integer *, 
00162             real *, integer *), slaset_(char *, integer *, integer *, 
00163             real *, real *, real *, integer *), slasum_(char *, 
00164             integer *, integer *, integer *), stgevc_(char *, char *, 
00165             logical *, integer *, real *, integer *, real *, integer *, real *
00166 , integer *, real *, integer *, integer *, integer *, real *, 
00167             integer *);
00168     real ulpinv;
00169     integer lwkopt, mtypes, ntestt;
00170 
00171     /* Fortran I/O blocks */
00172     static cilist io___40 = { 0, 0, 0, fmt_9999, 0 };
00173     static cilist io___41 = { 0, 0, 0, fmt_9999, 0 };
00174     static cilist io___42 = { 0, 0, 0, fmt_9999, 0 };
00175     static cilist io___43 = { 0, 0, 0, fmt_9999, 0 };
00176     static cilist io___44 = { 0, 0, 0, fmt_9999, 0 };
00177     static cilist io___45 = { 0, 0, 0, fmt_9999, 0 };
00178     static cilist io___46 = { 0, 0, 0, fmt_9999, 0 };
00179     static cilist io___47 = { 0, 0, 0, fmt_9999, 0 };
00180     static cilist io___50 = { 0, 0, 0, fmt_9999, 0 };
00181     static cilist io___51 = { 0, 0, 0, fmt_9999, 0 };
00182     static cilist io___52 = { 0, 0, 0, fmt_9998, 0 };
00183     static cilist io___53 = { 0, 0, 0, fmt_9999, 0 };
00184     static cilist io___54 = { 0, 0, 0, fmt_9998, 0 };
00185     static cilist io___55 = { 0, 0, 0, fmt_9999, 0 };
00186     static cilist io___56 = { 0, 0, 0, fmt_9999, 0 };
00187     static cilist io___57 = { 0, 0, 0, fmt_9998, 0 };
00188     static cilist io___58 = { 0, 0, 0, fmt_9999, 0 };
00189     static cilist io___59 = { 0, 0, 0, fmt_9998, 0 };
00190     static cilist io___62 = { 0, 0, 0, fmt_9997, 0 };
00191     static cilist io___63 = { 0, 0, 0, fmt_9996, 0 };
00192     static cilist io___64 = { 0, 0, 0, fmt_9995, 0 };
00193     static cilist io___65 = { 0, 0, 0, fmt_9994, 0 };
00194     static cilist io___66 = { 0, 0, 0, fmt_9993, 0 };
00195     static cilist io___67 = { 0, 0, 0, fmt_9992, 0 };
00196     static cilist io___68 = { 0, 0, 0, fmt_9991, 0 };
00197 
00198 
00199 
00200 /*  -- LAPACK test routine (version 3.1) -- */
00201 /*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd.. */
00202 /*     November 2006 */
00203 
00204 /*     .. Scalar Arguments .. */
00205 /*     .. */
00206 /*     .. Array Arguments .. */
00207 /*     .. */
00208 
00209 /*  Purpose */
00210 /*  ======= */
00211 
00212 /*  SCHKGG  checks the nonsymmetric generalized eigenvalue problem */
00213 /*  routines. */
00214 /*                                 T          T        T */
00215 /*  SGGHRD factors A and B as U H V  and U T V , where   means */
00216 /*  transpose, H is hessenberg, T is triangular and U and V are */
00217 /*  orthogonal. */
00218 /*                                  T          T */
00219 /*  SHGEQZ factors H and T as  Q S Z  and Q P Z , where P is upper */
00220 /*  triangular, S is in generalized Schur form (block upper triangular, */
00221 /*  with 1x1 and 2x2 blocks on the diagonal, the 2x2 blocks */
00222 /*  corresponding to complex conjugate pairs of generalized */
00223 /*  eigenvalues), and Q and Z are orthogonal.  It also computes the */
00224 /*  generalized eigenvalues (alpha(1),beta(1)),...,(alpha(n),beta(n)), */
00225 /*  where alpha(j)=S(j,j) and beta(j)=P(j,j) -- thus, */
00226 /*  w(j) = alpha(j)/beta(j) is a root of the generalized eigenvalue */
00227 /*  problem */
00228 
00229 /*      det( A - w(j) B ) = 0 */
00230 
00231 /*  and m(j) = beta(j)/alpha(j) is a root of the essentially equivalent */
00232 /*  problem */
00233 
00234 /*      det( m(j) A - B ) = 0 */
00235 
00236 /*  STGEVC computes the matrix L of left eigenvectors and the matrix R */
00237 /*  of right eigenvectors for the matrix pair ( S, P ).  In the */
00238 /*  description below,  l and r are left and right eigenvectors */
00239 /*  corresponding to the generalized eigenvalues (alpha,beta). */
00240 
00241 /*  When SCHKGG is called, a number of matrix "sizes" ("n's") and a */
00242 /*  number of matrix "types" are specified.  For each size ("n") */
00243 /*  and each type of matrix, one matrix will be generated and used */
00244 /*  to test the nonsymmetric eigenroutines.  For each matrix, 15 */
00245 /*  tests will be performed.  The first twelve "test ratios" should be */
00246 /*  small -- O(1).  They will be compared with the threshhold THRESH: */
00247 
00248 /*                   T */
00249 /*  (1)   | A - U H V  | / ( |A| n ulp ) */
00250 
00251 /*                   T */
00252 /*  (2)   | B - U T V  | / ( |B| n ulp ) */
00253 
00254 /*                T */
00255 /*  (3)   | I - UU  | / ( n ulp ) */
00256 
00257 /*                T */
00258 /*  (4)   | I - VV  | / ( n ulp ) */
00259 
00260 /*                   T */
00261 /*  (5)   | H - Q S Z  | / ( |H| n ulp ) */
00262 
00263 /*                   T */
00264 /*  (6)   | T - Q P Z  | / ( |T| n ulp ) */
00265 
00266 /*                T */
00267 /*  (7)   | I - QQ  | / ( n ulp ) */
00268 
00269 /*                T */
00270 /*  (8)   | I - ZZ  | / ( n ulp ) */
00271 
00272 /*  (9)   max over all left eigenvalue/-vector pairs (beta/alpha,l) of */
00273 
00274 /*     | l**H * (beta S - alpha P) | / ( ulp max( |beta S|, |alpha P| ) ) */
00275 
00276 /*  (10)  max over all left eigenvalue/-vector pairs (beta/alpha,l') of */
00277 /*                            T */
00278 /*    | l'**H * (beta H - alpha T) | / ( ulp max( |beta H|, |alpha T| ) ) */
00279 
00280 /*        where the eigenvectors l' are the result of passing Q to */
00281 /*        STGEVC and back transforming (HOWMNY='B'). */
00282 
00283 /*  (11)  max over all right eigenvalue/-vector pairs (beta/alpha,r) of */
00284 
00285 /*        | (beta S - alpha T) r | / ( ulp max( |beta S|, |alpha T| ) ) */
00286 
00287 /*  (12)  max over all right eigenvalue/-vector pairs (beta/alpha,r') of */
00288 
00289 /*        | (beta H - alpha T) r' | / ( ulp max( |beta H|, |alpha T| ) ) */
00290 
00291 /*        where the eigenvectors r' are the result of passing Z to */
00292 /*        STGEVC and back transforming (HOWMNY='B'). */
00293 
00294 /*  The last three test ratios will usually be small, but there is no */
00295 /*  mathematical requirement that they be so.  They are therefore */
00296 /*  compared with THRESH only if TSTDIF is .TRUE. */
00297 
00298 /*  (13)  | S(Q,Z computed) - S(Q,Z not computed) | / ( |S| ulp ) */
00299 
00300 /*  (14)  | P(Q,Z computed) - P(Q,Z not computed) | / ( |P| ulp ) */
00301 
00302 /*  (15)  max( |alpha(Q,Z computed) - alpha(Q,Z not computed)|/|S| , */
00303 /*             |beta(Q,Z computed) - beta(Q,Z not computed)|/|P| ) / ulp */
00304 
00305 /*  In addition, the normalization of L and R are checked, and compared */
00306 /*  with the threshhold THRSHN. */
00307 
00308 /*  Test Matrices */
00309 /*  ---- -------- */
00310 
00311 /*  The sizes of the test matrices are specified by an array */
00312 /*  NN(1:NSIZES); the value of each element NN(j) specifies one size. */
00313 /*  The "types" are specified by a logical array DOTYPE( 1:NTYPES ); if */
00314 /*  DOTYPE(j) is .TRUE., then matrix type "j" will be generated. */
00315 /*  Currently, the list of possible types is: */
00316 
00317 /*  (1)  ( 0, 0 )         (a pair of zero matrices) */
00318 
00319 /*  (2)  ( I, 0 )         (an identity and a zero matrix) */
00320 
00321 /*  (3)  ( 0, I )         (an identity and a zero matrix) */
00322 
00323 /*  (4)  ( I, I )         (a pair of identity matrices) */
00324 
00325 /*          t   t */
00326 /*  (5)  ( J , J  )       (a pair of transposed Jordan blocks) */
00327 
00328 /*                                      t                ( I   0  ) */
00329 /*  (6)  ( X, Y )         where  X = ( J   0  )  and Y = (      t ) */
00330 /*                                   ( 0   I  )          ( 0   J  ) */
00331 /*                        and I is a k x k identity and J a (k+1)x(k+1) */
00332 /*                        Jordan block; k=(N-1)/2 */
00333 
00334 /*  (7)  ( D, I )         where D is diag( 0, 1,..., N-1 ) (a diagonal */
00335 /*                        matrix with those diagonal entries.) */
00336 /*  (8)  ( I, D ) */
00337 
00338 /*  (9)  ( big*D, small*I ) where "big" is near overflow and small=1/big */
00339 
00340 /*  (10) ( small*D, big*I ) */
00341 
00342 /*  (11) ( big*I, small*D ) */
00343 
00344 /*  (12) ( small*I, big*D ) */
00345 
00346 /*  (13) ( big*D, big*I ) */
00347 
00348 /*  (14) ( small*D, small*I ) */
00349 
00350 /*  (15) ( D1, D2 )        where D1 is diag( 0, 0, 1, ..., N-3, 0 ) and */
00351 /*                         D2 is diag( 0, N-3, N-4,..., 1, 0, 0 ) */
00352 /*            t   t */
00353 /*  (16) U ( J , J ) V     where U and V are random orthogonal matrices. */
00354 
00355 /*  (17) U ( T1, T2 ) V    where T1 and T2 are upper triangular matrices */
00356 /*                         with random O(1) entries above the diagonal */
00357 /*                         and diagonal entries diag(T1) = */
00358 /*                         ( 0, 0, 1, ..., N-3, 0 ) and diag(T2) = */
00359 /*                         ( 0, N-3, N-4,..., 1, 0, 0 ) */
00360 
00361 /*  (18) U ( T1, T2 ) V    diag(T1) = ( 0, 0, 1, 1, s, ..., s, 0 ) */
00362 /*                         diag(T2) = ( 0, 1, 0, 1,..., 1, 0 ) */
00363 /*                         s = machine precision. */
00364 
00365 /*  (19) U ( T1, T2 ) V    diag(T1)=( 0,0,1,1, 1-d, ..., 1-(N-5)*d=s, 0 ) */
00366 /*                         diag(T2) = ( 0, 1, 0, 1, ..., 1, 0 ) */
00367 
00368 /*                                                         N-5 */
00369 /*  (20) U ( T1, T2 ) V    diag(T1)=( 0, 0, 1, 1, a, ..., a   =s, 0 ) */
00370 /*                         diag(T2) = ( 0, 1, 0, 1, ..., 1, 0, 0 ) */
00371 
00372 /*  (21) U ( T1, T2 ) V    diag(T1)=( 0, 0, 1, r1, r2, ..., r(N-4), 0 ) */
00373 /*                         diag(T2) = ( 0, 1, 0, 1, ..., 1, 0, 0 ) */
00374 /*                         where r1,..., r(N-4) are random. */
00375 
00376 /*  (22) U ( big*T1, small*T2 ) V    diag(T1) = ( 0, 0, 1, ..., N-3, 0 ) */
00377 /*                                   diag(T2) = ( 0, 1, ..., 1, 0, 0 ) */
00378 
00379 /*  (23) U ( small*T1, big*T2 ) V    diag(T1) = ( 0, 0, 1, ..., N-3, 0 ) */
00380 /*                                   diag(T2) = ( 0, 1, ..., 1, 0, 0 ) */
00381 
00382 /*  (24) U ( small*T1, small*T2 ) V  diag(T1) = ( 0, 0, 1, ..., N-3, 0 ) */
00383 /*                                   diag(T2) = ( 0, 1, ..., 1, 0, 0 ) */
00384 
00385 /*  (25) U ( big*T1, big*T2 ) V      diag(T1) = ( 0, 0, 1, ..., N-3, 0 ) */
00386 /*                                   diag(T2) = ( 0, 1, ..., 1, 0, 0 ) */
00387 
00388 /*  (26) U ( T1, T2 ) V     where T1 and T2 are random upper-triangular */
00389 /*                          matrices. */
00390 
00391 /*  Arguments */
00392 /*  ========= */
00393 
00394 /*  NSIZES  (input) INTEGER */
00395 /*          The number of sizes of matrices to use.  If it is zero, */
00396 /*          SCHKGG does nothing.  It must be at least zero. */
00397 
00398 /*  NN      (input) INTEGER array, dimension (NSIZES) */
00399 /*          An array containing the sizes to be used for the matrices. */
00400 /*          Zero values will be skipped.  The values must be at least */
00401 /*          zero. */
00402 
00403 /*  NTYPES  (input) INTEGER */
00404 /*          The number of elements in DOTYPE.   If it is zero, SCHKGG */
00405 /*          does nothing.  It must be at least zero.  If it is MAXTYP+1 */
00406 /*          and NSIZES is 1, then an additional type, MAXTYP+1 is */
00407 /*          defined, which is to use whatever matrix is in A.  This */
00408 /*          is only useful if DOTYPE(1:MAXTYP) is .FALSE. and */
00409 /*          DOTYPE(MAXTYP+1) is .TRUE. . */
00410 
00411 /*  DOTYPE  (input) LOGICAL array, dimension (NTYPES) */
00412 /*          If DOTYPE(j) is .TRUE., then for each size in NN a */
00413 /*          matrix of that size and of type j will be generated. */
00414 /*          If NTYPES is smaller than the maximum number of types */
00415 /*          defined (PARAMETER MAXTYP), then types NTYPES+1 through */
00416 /*          MAXTYP will not be generated.  If NTYPES is larger */
00417 /*          than MAXTYP, DOTYPE(MAXTYP+1) through DOTYPE(NTYPES) */
00418 /*          will be ignored. */
00419 
00420 /*  ISEED   (input/output) INTEGER array, dimension (4) */
00421 /*          On entry ISEED specifies the seed of the random number */
00422 /*          generator. The array elements should be between 0 and 4095; */
00423 /*          if not they will be reduced mod 4096.  Also, ISEED(4) must */
00424 /*          be odd.  The random number generator uses a linear */
00425 /*          congruential sequence limited to small integers, and so */
00426 /*          should produce machine independent random numbers. The */
00427 /*          values of ISEED are changed on exit, and can be used in the */
00428 /*          next call to SCHKGG to continue the same random number */
00429 /*          sequence. */
00430 
00431 /*  THRESH  (input) REAL */
00432 /*          A test will count as "failed" if the "error", computed as */
00433 /*          described above, exceeds THRESH.  Note that the error is */
00434 /*          scaled to be O(1), so THRESH should be a reasonably small */
00435 /*          multiple of 1, e.g., 10 or 100.  In particular, it should */
00436 /*          not depend on the precision (single vs. double) or the size */
00437 /*          of the matrix.  It must be at least zero. */
00438 
00439 /*  TSTDIF  (input) LOGICAL */
00440 /*          Specifies whether test ratios 13-15 will be computed and */
00441 /*          compared with THRESH. */
00442 /*          = .FALSE.: Only test ratios 1-12 will be computed and tested. */
00443 /*                     Ratios 13-15 will be set to zero. */
00444 /*          = .TRUE.:  All the test ratios 1-15 will be computed and */
00445 /*                     tested. */
00446 
00447 /*  THRSHN  (input) REAL */
00448 /*          Threshhold for reporting eigenvector normalization error. */
00449 /*          If the normalization of any eigenvector differs from 1 by */
00450 /*          more than THRSHN*ulp, then a special error message will be */
00451 /*          printed.  (This is handled separately from the other tests, */
00452 /*          since only a compiler or programming error should cause an */
00453 /*          error message, at least if THRSHN is at least 5--10.) */
00454 
00455 /*  NOUNIT  (input) INTEGER */
00456 /*          The FORTRAN unit number for printing out error messages */
00457 /*          (e.g., if a routine returns IINFO not equal to 0.) */
00458 
00459 /*  A       (input/workspace) REAL array, dimension */
00460 /*                            (LDA, max(NN)) */
00461 /*          Used to hold the original A matrix.  Used as input only */
00462 /*          if NTYPES=MAXTYP+1, DOTYPE(1:MAXTYP)=.FALSE., and */
00463 /*          DOTYPE(MAXTYP+1)=.TRUE. */
00464 
00465 /*  LDA     (input) INTEGER */
00466 /*          The leading dimension of A, B, H, T, S1, P1, S2, and P2. */
00467 /*          It must be at least 1 and at least max( NN ). */
00468 
00469 /*  B       (input/workspace) REAL array, dimension */
00470 /*                            (LDA, max(NN)) */
00471 /*          Used to hold the original B matrix.  Used as input only */
00472 /*          if NTYPES=MAXTYP+1, DOTYPE(1:MAXTYP)=.FALSE., and */
00473 /*          DOTYPE(MAXTYP+1)=.TRUE. */
00474 
00475 /*  H       (workspace) REAL array, dimension (LDA, max(NN)) */
00476 /*          The upper Hessenberg matrix computed from A by SGGHRD. */
00477 
00478 /*  T       (workspace) REAL array, dimension (LDA, max(NN)) */
00479 /*          The upper triangular matrix computed from B by SGGHRD. */
00480 
00481 /*  S1      (workspace) REAL array, dimension (LDA, max(NN)) */
00482 /*          The Schur (block upper triangular) matrix computed from H by */
00483 /*          SHGEQZ when Q and Z are also computed. */
00484 
00485 /*  S2      (workspace) REAL array, dimension (LDA, max(NN)) */
00486 /*          The Schur (block upper triangular) matrix computed from H by */
00487 /*          SHGEQZ when Q and Z are not computed. */
00488 
00489 /*  P1      (workspace) REAL array, dimension (LDA, max(NN)) */
00490 /*          The upper triangular matrix computed from T by SHGEQZ */
00491 /*          when Q and Z are also computed. */
00492 
00493 /*  P2      (workspace) REAL array, dimension (LDA, max(NN)) */
00494 /*          The upper triangular matrix computed from T by SHGEQZ */
00495 /*          when Q and Z are not computed. */
00496 
00497 /*  U       (workspace) REAL array, dimension (LDU, max(NN)) */
00498 /*          The (left) orthogonal matrix computed by SGGHRD. */
00499 
00500 /*  LDU     (input) INTEGER */
00501 /*          The leading dimension of U, V, Q, Z, EVECTL, and EVECTR.  It */
00502 /*          must be at least 1 and at least max( NN ). */
00503 
00504 /*  V       (workspace) REAL array, dimension (LDU, max(NN)) */
00505 /*          The (right) orthogonal matrix computed by SGGHRD. */
00506 
00507 /*  Q       (workspace) REAL array, dimension (LDU, max(NN)) */
00508 /*          The (left) orthogonal matrix computed by SHGEQZ. */
00509 
00510 /*  Z       (workspace) REAL array, dimension (LDU, max(NN)) */
00511 /*          The (left) orthogonal matrix computed by SHGEQZ. */
00512 
00513 /*  ALPHR1  (workspace) REAL array, dimension (max(NN)) */
00514 /*  ALPHI1  (workspace) REAL array, dimension (max(NN)) */
00515 /*  BETA1   (workspace) REAL array, dimension (max(NN)) */
00516 
00517 /*          The generalized eigenvalues of (A,B) computed by SHGEQZ */
00518 /*          when Q, Z, and the full Schur matrices are computed. */
00519 /*          On exit, ( ALPHR1(k)+ALPHI1(k)*i ) / BETA1(k) is the k-th */
00520 /*          generalized eigenvalue of the matrices in A and B. */
00521 
00522 /*  ALPHR3  (workspace) REAL array, dimension (max(NN)) */
00523 /*  ALPHI3  (workspace) REAL array, dimension (max(NN)) */
00524 /*  BETA3   (workspace) REAL array, dimension (max(NN)) */
00525 
00526 /*  EVECTL  (workspace) REAL array, dimension (LDU, max(NN)) */
00527 /*          The (block lower triangular) left eigenvector matrix for */
00528 /*          the matrices in S1 and P1.  (See STGEVC for the format.) */
00529 
00530 /*  EVECTR  (workspace) REAL array, dimension (LDU, max(NN)) */
00531 /*          The (block upper triangular) right eigenvector matrix for */
00532 /*          the matrices in S1 and P1.  (See STGEVC for the format.) */
00533 
00534 /*  WORK    (workspace) REAL array, dimension (LWORK) */
00535 
00536 /*  LWORK   (input) INTEGER */
00537 /*          The number of entries in WORK.  This must be at least */
00538 /*          max( 2 * N**2, 6*N, 1 ), for all N=NN(j). */
00539 
00540 /*  LLWORK  (workspace) LOGICAL array, dimension (max(NN)) */
00541 
00542 /*  RESULT  (output) REAL array, dimension (15) */
00543 /*          The values computed by the tests described above. */
00544 /*          The values are currently limited to 1/ulp, to avoid */
00545 /*          overflow. */
00546 
00547 /*  INFO    (output) INTEGER */
00548 /*          = 0:  successful exit */
00549 /*          < 0:  if INFO = -i, the i-th argument had an illegal value */
00550 /*          > 0:  A routine returned an error code.  INFO is the */
00551 /*                absolute value of the INFO value returned. */
00552 
00553 /*  ===================================================================== */
00554 
00555 /*     .. Parameters .. */
00556 /*     .. */
00557 /*     .. Local Scalars .. */
00558 /*     .. */
00559 /*     .. Local Arrays .. */
00560 /*     .. */
00561 /*     .. External Functions .. */
00562 /*     .. */
00563 /*     .. External Subroutines .. */
00564 /*     .. */
00565 /*     .. Intrinsic Functions .. */
00566 /*     .. */
00567 /*     .. Data statements .. */
00568     /* Parameter adjustments */
00569     --nn;
00570     --dotype;
00571     --iseed;
00572     p2_dim1 = *lda;
00573     p2_offset = 1 + p2_dim1;
00574     p2 -= p2_offset;
00575     p1_dim1 = *lda;
00576     p1_offset = 1 + p1_dim1;
00577     p1 -= p1_offset;
00578     s2_dim1 = *lda;
00579     s2_offset = 1 + s2_dim1;
00580     s2 -= s2_offset;
00581     s1_dim1 = *lda;
00582     s1_offset = 1 + s1_dim1;
00583     s1 -= s1_offset;
00584     t_dim1 = *lda;
00585     t_offset = 1 + t_dim1;
00586     t -= t_offset;
00587     h_dim1 = *lda;
00588     h_offset = 1 + h_dim1;
00589     h__ -= h_offset;
00590     b_dim1 = *lda;
00591     b_offset = 1 + b_dim1;
00592     b -= b_offset;
00593     a_dim1 = *lda;
00594     a_offset = 1 + a_dim1;
00595     a -= a_offset;
00596     evectr_dim1 = *ldu;
00597     evectr_offset = 1 + evectr_dim1;
00598     evectr -= evectr_offset;
00599     evectl_dim1 = *ldu;
00600     evectl_offset = 1 + evectl_dim1;
00601     evectl -= evectl_offset;
00602     z_dim1 = *ldu;
00603     z_offset = 1 + z_dim1;
00604     z__ -= z_offset;
00605     q_dim1 = *ldu;
00606     q_offset = 1 + q_dim1;
00607     q -= q_offset;
00608     v_dim1 = *ldu;
00609     v_offset = 1 + v_dim1;
00610     v -= v_offset;
00611     u_dim1 = *ldu;
00612     u_offset = 1 + u_dim1;
00613     u -= u_offset;
00614     --alphr1;
00615     --alphi1;
00616     --beta1;
00617     --alphr3;
00618     --alphi3;
00619     --beta3;
00620     --work;
00621     --llwork;
00622     --result;
00623 
00624     /* Function Body */
00625 /*     .. */
00626 /*     .. Executable Statements .. */
00627 
00628 /*     Check for errors */
00629 
00630     *info = 0;
00631 
00632     badnn = FALSE_;
00633     nmax = 1;
00634     i__1 = *nsizes;
00635     for (j = 1; j <= i__1; ++j) {
00636 /* Computing MAX */
00637         i__2 = nmax, i__3 = nn[j];
00638         nmax = max(i__2,i__3);
00639         if (nn[j] < 0) {
00640             badnn = TRUE_;
00641         }
00642 /* L10: */
00643     }
00644 
00645 /*     Maximum blocksize and shift -- we assume that blocksize and number */
00646 /*     of shifts are monotone increasing functions of N. */
00647 
00648 /* Computing MAX */
00649     i__1 = nmax * 6, i__2 = (nmax << 1) * nmax, i__1 = max(i__1,i__2);
00650     lwkopt = max(i__1,1);
00651 
00652 /*     Check for errors */
00653 
00654     if (*nsizes < 0) {
00655         *info = -1;
00656     } else if (badnn) {
00657         *info = -2;
00658     } else if (*ntypes < 0) {
00659         *info = -3;
00660     } else if (*thresh < 0.f) {
00661         *info = -6;
00662     } else if (*lda <= 1 || *lda < nmax) {
00663         *info = -10;
00664     } else if (*ldu <= 1 || *ldu < nmax) {
00665         *info = -19;
00666     } else if (lwkopt > *lwork) {
00667         *info = -30;
00668     }
00669 
00670     if (*info != 0) {
00671         i__1 = -(*info);
00672         xerbla_("SCHKGG", &i__1);
00673         return 0;
00674     }
00675 
00676 /*     Quick return if possible */
00677 
00678     if (*nsizes == 0 || *ntypes == 0) {
00679         return 0;
00680     }
00681 
00682     safmin = slamch_("Safe minimum");
00683     ulp = slamch_("Epsilon") * slamch_("Base");
00684     safmin /= ulp;
00685     safmax = 1.f / safmin;
00686     slabad_(&safmin, &safmax);
00687     ulpinv = 1.f / ulp;
00688 
00689 /*     The values RMAGN(2:3) depend on N, see below. */
00690 
00691     rmagn[0] = 0.f;
00692     rmagn[1] = 1.f;
00693 
00694 /*     Loop over sizes, types */
00695 
00696     ntestt = 0;
00697     nerrs = 0;
00698     nmats = 0;
00699 
00700     i__1 = *nsizes;
00701     for (jsize = 1; jsize <= i__1; ++jsize) {
00702         n = nn[jsize];
00703         n1 = max(1,n);
00704         rmagn[2] = safmax * ulp / (real) n1;
00705         rmagn[3] = safmin * ulpinv * n1;
00706 
00707         if (*nsizes != 1) {
00708             mtypes = min(26,*ntypes);
00709         } else {
00710             mtypes = min(27,*ntypes);
00711         }
00712 
00713         i__2 = mtypes;
00714         for (jtype = 1; jtype <= i__2; ++jtype) {
00715             if (! dotype[jtype]) {
00716                 goto L230;
00717             }
00718             ++nmats;
00719             ntest = 0;
00720 
00721 /*           Save ISEED in case of an error. */
00722 
00723             for (j = 1; j <= 4; ++j) {
00724                 ioldsd[j - 1] = iseed[j];
00725 /* L20: */
00726             }
00727 
00728 /*           Initialize RESULT */
00729 
00730             for (j = 1; j <= 15; ++j) {
00731                 result[j] = 0.f;
00732 /* L30: */
00733             }
00734 
00735 /*           Compute A and B */
00736 
00737 /*           Description of control parameters: */
00738 
00739 /*           KCLASS: =1 means w/o rotation, =2 means w/ rotation, */
00740 /*                   =3 means random. */
00741 /*           KATYPE: the "type" to be passed to SLATM4 for computing A. */
00742 /*           KAZERO: the pattern of zeros on the diagonal for A: */
00743 /*                   =1: ( xxx ), =2: (0, xxx ) =3: ( 0, 0, xxx, 0 ), */
00744 /*                   =4: ( 0, xxx, 0, 0 ), =5: ( 0, 0, 1, xxx, 0 ), */
00745 /*                   =6: ( 0, 1, 0, xxx, 0 ).  (xxx means a string of */
00746 /*                   non-zero entries.) */
00747 /*           KAMAGN: the magnitude of the matrix: =0: zero, =1: O(1), */
00748 /*                   =2: large, =3: small. */
00749 /*           IASIGN: 1 if the diagonal elements of A are to be */
00750 /*                   multiplied by a random magnitude 1 number, =2 if */
00751 /*                   randomly chosen diagonal blocks are to be rotated */
00752 /*                   to form 2x2 blocks. */
00753 /*           KBTYPE, KBZERO, KBMAGN, IBSIGN: the same, but for B. */
00754 /*           KTRIAN: =0: don't fill in the upper triangle, =1: do. */
00755 /*           KZ1, KZ2, KADD: used to implement KAZERO and KBZERO. */
00756 /*           RMAGN: used to implement KAMAGN and KBMAGN. */
00757 
00758             if (mtypes > 26) {
00759                 goto L110;
00760             }
00761             iinfo = 0;
00762             if (kclass[jtype - 1] < 3) {
00763 
00764 /*              Generate A (w/o rotation) */
00765 
00766                 if ((i__3 = katype[jtype - 1], abs(i__3)) == 3) {
00767                     in = ((n - 1) / 2 << 1) + 1;
00768                     if (in != n) {
00769                         slaset_("Full", &n, &n, &c_b13, &c_b13, &a[a_offset], 
00770                                 lda);
00771                     }
00772                 } else {
00773                     in = n;
00774                 }
00775                 slatm4_(&katype[jtype - 1], &in, &kz1[kazero[jtype - 1] - 1], 
00776                         &kz2[kazero[jtype - 1] - 1], &iasign[jtype - 1], &
00777                         rmagn[kamagn[jtype - 1]], &ulp, &rmagn[ktrian[jtype - 
00778                         1] * kamagn[jtype - 1]], &c__2, &iseed[1], &a[
00779                         a_offset], lda);
00780                 iadd = kadd[kazero[jtype - 1] - 1];
00781                 if (iadd > 0 && iadd <= n) {
00782                     a[iadd + iadd * a_dim1] = rmagn[kamagn[jtype - 1]];
00783                 }
00784 
00785 /*              Generate B (w/o rotation) */
00786 
00787                 if ((i__3 = kbtype[jtype - 1], abs(i__3)) == 3) {
00788                     in = ((n - 1) / 2 << 1) + 1;
00789                     if (in != n) {
00790                         slaset_("Full", &n, &n, &c_b13, &c_b13, &b[b_offset], 
00791                                 lda);
00792                     }
00793                 } else {
00794                     in = n;
00795                 }
00796                 slatm4_(&kbtype[jtype - 1], &in, &kz1[kbzero[jtype - 1] - 1], 
00797                         &kz2[kbzero[jtype - 1] - 1], &ibsign[jtype - 1], &
00798                         rmagn[kbmagn[jtype - 1]], &c_b19, &rmagn[ktrian[jtype 
00799                         - 1] * kbmagn[jtype - 1]], &c__2, &iseed[1], &b[
00800                         b_offset], lda);
00801                 iadd = kadd[kbzero[jtype - 1] - 1];
00802                 if (iadd != 0 && iadd <= n) {
00803                     b[iadd + iadd * b_dim1] = rmagn[kbmagn[jtype - 1]];
00804                 }
00805 
00806                 if (kclass[jtype - 1] == 2 && n > 0) {
00807 
00808 /*                 Include rotations */
00809 
00810 /*                 Generate U, V as Householder transformations times */
00811 /*                 a diagonal matrix. */
00812 
00813                     i__3 = n - 1;
00814                     for (jc = 1; jc <= i__3; ++jc) {
00815                         i__4 = n;
00816                         for (jr = jc; jr <= i__4; ++jr) {
00817                             u[jr + jc * u_dim1] = slarnd_(&c__3, &iseed[1]);
00818                             v[jr + jc * v_dim1] = slarnd_(&c__3, &iseed[1]);
00819 /* L40: */
00820                         }
00821                         i__4 = n + 1 - jc;
00822                         slarfg_(&i__4, &u[jc + jc * u_dim1], &u[jc + 1 + jc * 
00823                                 u_dim1], &c__1, &work[jc]);
00824                         work[(n << 1) + jc] = r_sign(&c_b19, &u[jc + jc * 
00825                                 u_dim1]);
00826                         u[jc + jc * u_dim1] = 1.f;
00827                         i__4 = n + 1 - jc;
00828                         slarfg_(&i__4, &v[jc + jc * v_dim1], &v[jc + 1 + jc * 
00829                                 v_dim1], &c__1, &work[n + jc]);
00830                         work[n * 3 + jc] = r_sign(&c_b19, &v[jc + jc * v_dim1]
00831                                 );
00832                         v[jc + jc * v_dim1] = 1.f;
00833 /* L50: */
00834                     }
00835                     u[n + n * u_dim1] = 1.f;
00836                     work[n] = 0.f;
00837                     r__1 = slarnd_(&c__2, &iseed[1]);
00838                     work[n * 3] = r_sign(&c_b19, &r__1);
00839                     v[n + n * v_dim1] = 1.f;
00840                     work[n * 2] = 0.f;
00841                     r__1 = slarnd_(&c__2, &iseed[1]);
00842                     work[n * 4] = r_sign(&c_b19, &r__1);
00843 
00844 /*                 Apply the diagonal matrices */
00845 
00846                     i__3 = n;
00847                     for (jc = 1; jc <= i__3; ++jc) {
00848                         i__4 = n;
00849                         for (jr = 1; jr <= i__4; ++jr) {
00850                             a[jr + jc * a_dim1] = work[(n << 1) + jr] * work[
00851                                     n * 3 + jc] * a[jr + jc * a_dim1];
00852                             b[jr + jc * b_dim1] = work[(n << 1) + jr] * work[
00853                                     n * 3 + jc] * b[jr + jc * b_dim1];
00854 /* L60: */
00855                         }
00856 /* L70: */
00857                     }
00858                     i__3 = n - 1;
00859                     sorm2r_("L", "N", &n, &n, &i__3, &u[u_offset], ldu, &work[
00860                             1], &a[a_offset], lda, &work[(n << 1) + 1], &
00861                             iinfo);
00862                     if (iinfo != 0) {
00863                         goto L100;
00864                     }
00865                     i__3 = n - 1;
00866                     sorm2r_("R", "T", &n, &n, &i__3, &v[v_offset], ldu, &work[
00867                             n + 1], &a[a_offset], lda, &work[(n << 1) + 1], &
00868                             iinfo);
00869                     if (iinfo != 0) {
00870                         goto L100;
00871                     }
00872                     i__3 = n - 1;
00873                     sorm2r_("L", "N", &n, &n, &i__3, &u[u_offset], ldu, &work[
00874                             1], &b[b_offset], lda, &work[(n << 1) + 1], &
00875                             iinfo);
00876                     if (iinfo != 0) {
00877                         goto L100;
00878                     }
00879                     i__3 = n - 1;
00880                     sorm2r_("R", "T", &n, &n, &i__3, &v[v_offset], ldu, &work[
00881                             n + 1], &b[b_offset], lda, &work[(n << 1) + 1], &
00882                             iinfo);
00883                     if (iinfo != 0) {
00884                         goto L100;
00885                     }
00886                 }
00887             } else {
00888 
00889 /*              Random matrices */
00890 
00891                 i__3 = n;
00892                 for (jc = 1; jc <= i__3; ++jc) {
00893                     i__4 = n;
00894                     for (jr = 1; jr <= i__4; ++jr) {
00895                         a[jr + jc * a_dim1] = rmagn[kamagn[jtype - 1]] * 
00896                                 slarnd_(&c__2, &iseed[1]);
00897                         b[jr + jc * b_dim1] = rmagn[kbmagn[jtype - 1]] * 
00898                                 slarnd_(&c__2, &iseed[1]);
00899 /* L80: */
00900                     }
00901 /* L90: */
00902                 }
00903             }
00904 
00905             anorm = slange_("1", &n, &n, &a[a_offset], lda, &work[1]);
00906             bnorm = slange_("1", &n, &n, &b[b_offset], lda, &work[1]);
00907 
00908 L100:
00909 
00910             if (iinfo != 0) {
00911                 io___40.ciunit = *nounit;
00912                 s_wsfe(&io___40);
00913                 do_fio(&c__1, "Generator", (ftnlen)9);
00914                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
00915                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
00916                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
00917                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
00918                 e_wsfe();
00919                 *info = abs(iinfo);
00920                 return 0;
00921             }
00922 
00923 L110:
00924 
00925 /*           Call SGEQR2, SORM2R, and SGGHRD to compute H, T, U, and V */
00926 
00927             slacpy_(" ", &n, &n, &a[a_offset], lda, &h__[h_offset], lda);
00928             slacpy_(" ", &n, &n, &b[b_offset], lda, &t[t_offset], lda);
00929             ntest = 1;
00930             result[1] = ulpinv;
00931 
00932             sgeqr2_(&n, &n, &t[t_offset], lda, &work[1], &work[n + 1], &iinfo)
00933                     ;
00934             if (iinfo != 0) {
00935                 io___41.ciunit = *nounit;
00936                 s_wsfe(&io___41);
00937                 do_fio(&c__1, "SGEQR2", (ftnlen)6);
00938                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
00939                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
00940                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
00941                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
00942                 e_wsfe();
00943                 *info = abs(iinfo);
00944                 goto L210;
00945             }
00946 
00947             sorm2r_("L", "T", &n, &n, &n, &t[t_offset], lda, &work[1], &h__[
00948                     h_offset], lda, &work[n + 1], &iinfo);
00949             if (iinfo != 0) {
00950                 io___42.ciunit = *nounit;
00951                 s_wsfe(&io___42);
00952                 do_fio(&c__1, "SORM2R", (ftnlen)6);
00953                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
00954                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
00955                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
00956                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
00957                 e_wsfe();
00958                 *info = abs(iinfo);
00959                 goto L210;
00960             }
00961 
00962             slaset_("Full", &n, &n, &c_b13, &c_b19, &u[u_offset], ldu);
00963             sorm2r_("R", "N", &n, &n, &n, &t[t_offset], lda, &work[1], &u[
00964                     u_offset], ldu, &work[n + 1], &iinfo);
00965             if (iinfo != 0) {
00966                 io___43.ciunit = *nounit;
00967                 s_wsfe(&io___43);
00968                 do_fio(&c__1, "SORM2R", (ftnlen)6);
00969                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
00970                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
00971                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
00972                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
00973                 e_wsfe();
00974                 *info = abs(iinfo);
00975                 goto L210;
00976             }
00977 
00978             sgghrd_("V", "I", &n, &c__1, &n, &h__[h_offset], lda, &t[t_offset]
00979 , lda, &u[u_offset], ldu, &v[v_offset], ldu, &iinfo);
00980             if (iinfo != 0) {
00981                 io___44.ciunit = *nounit;
00982                 s_wsfe(&io___44);
00983                 do_fio(&c__1, "SGGHRD", (ftnlen)6);
00984                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
00985                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
00986                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
00987                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
00988                 e_wsfe();
00989                 *info = abs(iinfo);
00990                 goto L210;
00991             }
00992             ntest = 4;
00993 
00994 /*           Do tests 1--4 */
00995 
00996             sget51_(&c__1, &n, &a[a_offset], lda, &h__[h_offset], lda, &u[
00997                     u_offset], ldu, &v[v_offset], ldu, &work[1], &result[1]);
00998             sget51_(&c__1, &n, &b[b_offset], lda, &t[t_offset], lda, &u[
00999                     u_offset], ldu, &v[v_offset], ldu, &work[1], &result[2]);
01000             sget51_(&c__3, &n, &b[b_offset], lda, &t[t_offset], lda, &u[
01001                     u_offset], ldu, &u[u_offset], ldu, &work[1], &result[3]);
01002             sget51_(&c__3, &n, &b[b_offset], lda, &t[t_offset], lda, &v[
01003                     v_offset], ldu, &v[v_offset], ldu, &work[1], &result[4]);
01004 
01005 /*           Call SHGEQZ to compute S1, P1, S2, P2, Q, and Z, do tests. */
01006 
01007 /*           Compute T1 and UZ */
01008 
01009 /*           Eigenvalues only */
01010 
01011             slacpy_(" ", &n, &n, &h__[h_offset], lda, &s2[s2_offset], lda);
01012             slacpy_(" ", &n, &n, &t[t_offset], lda, &p2[p2_offset], lda);
01013             ntest = 5;
01014             result[5] = ulpinv;
01015 
01016             shgeqz_("E", "N", "N", &n, &c__1, &n, &s2[s2_offset], lda, &p2[
01017                     p2_offset], lda, &alphr3[1], &alphi3[1], &beta3[1], &q[
01018                     q_offset], ldu, &z__[z_offset], ldu, &work[1], lwork, &
01019                     iinfo);
01020             if (iinfo != 0) {
01021                 io___45.ciunit = *nounit;
01022                 s_wsfe(&io___45);
01023                 do_fio(&c__1, "SHGEQZ(E)", (ftnlen)9);
01024                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01025                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01026                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01027                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01028                 e_wsfe();
01029                 *info = abs(iinfo);
01030                 goto L210;
01031             }
01032 
01033 /*           Eigenvalues and Full Schur Form */
01034 
01035             slacpy_(" ", &n, &n, &h__[h_offset], lda, &s2[s2_offset], lda);
01036             slacpy_(" ", &n, &n, &t[t_offset], lda, &p2[p2_offset], lda);
01037 
01038             shgeqz_("S", "N", "N", &n, &c__1, &n, &s2[s2_offset], lda, &p2[
01039                     p2_offset], lda, &alphr1[1], &alphi1[1], &beta1[1], &q[
01040                     q_offset], ldu, &z__[z_offset], ldu, &work[1], lwork, &
01041                     iinfo);
01042             if (iinfo != 0) {
01043                 io___46.ciunit = *nounit;
01044                 s_wsfe(&io___46);
01045                 do_fio(&c__1, "SHGEQZ(S)", (ftnlen)9);
01046                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01047                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01048                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01049                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01050                 e_wsfe();
01051                 *info = abs(iinfo);
01052                 goto L210;
01053             }
01054 
01055 /*           Eigenvalues, Schur Form, and Schur Vectors */
01056 
01057             slacpy_(" ", &n, &n, &h__[h_offset], lda, &s1[s1_offset], lda);
01058             slacpy_(" ", &n, &n, &t[t_offset], lda, &p1[p1_offset], lda);
01059 
01060             shgeqz_("S", "I", "I", &n, &c__1, &n, &s1[s1_offset], lda, &p1[
01061                     p1_offset], lda, &alphr1[1], &alphi1[1], &beta1[1], &q[
01062                     q_offset], ldu, &z__[z_offset], ldu, &work[1], lwork, &
01063                     iinfo);
01064             if (iinfo != 0) {
01065                 io___47.ciunit = *nounit;
01066                 s_wsfe(&io___47);
01067                 do_fio(&c__1, "SHGEQZ(V)", (ftnlen)9);
01068                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01069                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01070                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01071                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01072                 e_wsfe();
01073                 *info = abs(iinfo);
01074                 goto L210;
01075             }
01076 
01077             ntest = 8;
01078 
01079 /*           Do Tests 5--8 */
01080 
01081             sget51_(&c__1, &n, &h__[h_offset], lda, &s1[s1_offset], lda, &q[
01082                     q_offset], ldu, &z__[z_offset], ldu, &work[1], &result[5])
01083                     ;
01084             sget51_(&c__1, &n, &t[t_offset], lda, &p1[p1_offset], lda, &q[
01085                     q_offset], ldu, &z__[z_offset], ldu, &work[1], &result[6])
01086                     ;
01087             sget51_(&c__3, &n, &t[t_offset], lda, &p1[p1_offset], lda, &q[
01088                     q_offset], ldu, &q[q_offset], ldu, &work[1], &result[7]);
01089             sget51_(&c__3, &n, &t[t_offset], lda, &p1[p1_offset], lda, &z__[
01090                     z_offset], ldu, &z__[z_offset], ldu, &work[1], &result[8])
01091                     ;
01092 
01093 /*           Compute the Left and Right Eigenvectors of (S1,P1) */
01094 
01095 /*           9: Compute the left eigenvector Matrix without */
01096 /*              back transforming: */
01097 
01098             ntest = 9;
01099             result[9] = ulpinv;
01100 
01101 /*           To test "SELECT" option, compute half of the eigenvectors */
01102 /*           in one call, and half in another */
01103 
01104             i1 = n / 2;
01105             i__3 = i1;
01106             for (j = 1; j <= i__3; ++j) {
01107                 llwork[j] = TRUE_;
01108 /* L120: */
01109             }
01110             i__3 = n;
01111             for (j = i1 + 1; j <= i__3; ++j) {
01112                 llwork[j] = FALSE_;
01113 /* L130: */
01114             }
01115 
01116             stgevc_("L", "S", &llwork[1], &n, &s1[s1_offset], lda, &p1[
01117                     p1_offset], lda, &evectl[evectl_offset], ldu, dumma, ldu, 
01118                     &n, &in, &work[1], &iinfo);
01119             if (iinfo != 0) {
01120                 io___50.ciunit = *nounit;
01121                 s_wsfe(&io___50);
01122                 do_fio(&c__1, "STGEVC(L,S1)", (ftnlen)12);
01123                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01124                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01125                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01126                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01127                 e_wsfe();
01128                 *info = abs(iinfo);
01129                 goto L210;
01130             }
01131 
01132             i1 = in;
01133             i__3 = i1;
01134             for (j = 1; j <= i__3; ++j) {
01135                 llwork[j] = FALSE_;
01136 /* L140: */
01137             }
01138             i__3 = n;
01139             for (j = i1 + 1; j <= i__3; ++j) {
01140                 llwork[j] = TRUE_;
01141 /* L150: */
01142             }
01143 
01144             stgevc_("L", "S", &llwork[1], &n, &s1[s1_offset], lda, &p1[
01145                     p1_offset], lda, &evectl[(i1 + 1) * evectl_dim1 + 1], ldu, 
01146                      dumma, ldu, &n, &in, &work[1], &iinfo);
01147             if (iinfo != 0) {
01148                 io___51.ciunit = *nounit;
01149                 s_wsfe(&io___51);
01150                 do_fio(&c__1, "STGEVC(L,S2)", (ftnlen)12);
01151                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01152                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01153                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01154                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01155                 e_wsfe();
01156                 *info = abs(iinfo);
01157                 goto L210;
01158             }
01159 
01160             sget52_(&c_true, &n, &s1[s1_offset], lda, &p1[p1_offset], lda, &
01161                     evectl[evectl_offset], ldu, &alphr1[1], &alphi1[1], &
01162                     beta1[1], &work[1], dumma);
01163             result[9] = dumma[0];
01164             if (dumma[1] > *thrshn) {
01165                 io___52.ciunit = *nounit;
01166                 s_wsfe(&io___52);
01167                 do_fio(&c__1, "Left", (ftnlen)4);
01168                 do_fio(&c__1, "STGEVC(HOWMNY=S)", (ftnlen)16);
01169                 do_fio(&c__1, (char *)&dumma[1], (ftnlen)sizeof(real));
01170                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01171                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01172                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01173                 e_wsfe();
01174             }
01175 
01176 /*           10: Compute the left eigenvector Matrix with */
01177 /*               back transforming: */
01178 
01179             ntest = 10;
01180             result[10] = ulpinv;
01181             slacpy_("F", &n, &n, &q[q_offset], ldu, &evectl[evectl_offset], 
01182                     ldu);
01183             stgevc_("L", "B", &llwork[1], &n, &s1[s1_offset], lda, &p1[
01184                     p1_offset], lda, &evectl[evectl_offset], ldu, dumma, ldu, 
01185                     &n, &in, &work[1], &iinfo);
01186             if (iinfo != 0) {
01187                 io___53.ciunit = *nounit;
01188                 s_wsfe(&io___53);
01189                 do_fio(&c__1, "STGEVC(L,B)", (ftnlen)11);
01190                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01191                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01192                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01193                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01194                 e_wsfe();
01195                 *info = abs(iinfo);
01196                 goto L210;
01197             }
01198 
01199             sget52_(&c_true, &n, &h__[h_offset], lda, &t[t_offset], lda, &
01200                     evectl[evectl_offset], ldu, &alphr1[1], &alphi1[1], &
01201                     beta1[1], &work[1], dumma);
01202             result[10] = dumma[0];
01203             if (dumma[1] > *thrshn) {
01204                 io___54.ciunit = *nounit;
01205                 s_wsfe(&io___54);
01206                 do_fio(&c__1, "Left", (ftnlen)4);
01207                 do_fio(&c__1, "STGEVC(HOWMNY=B)", (ftnlen)16);
01208                 do_fio(&c__1, (char *)&dumma[1], (ftnlen)sizeof(real));
01209                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01210                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01211                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01212                 e_wsfe();
01213             }
01214 
01215 /*           11: Compute the right eigenvector Matrix without */
01216 /*               back transforming: */
01217 
01218             ntest = 11;
01219             result[11] = ulpinv;
01220 
01221 /*           To test "SELECT" option, compute half of the eigenvectors */
01222 /*           in one call, and half in another */
01223 
01224             i1 = n / 2;
01225             i__3 = i1;
01226             for (j = 1; j <= i__3; ++j) {
01227                 llwork[j] = TRUE_;
01228 /* L160: */
01229             }
01230             i__3 = n;
01231             for (j = i1 + 1; j <= i__3; ++j) {
01232                 llwork[j] = FALSE_;
01233 /* L170: */
01234             }
01235 
01236             stgevc_("R", "S", &llwork[1], &n, &s1[s1_offset], lda, &p1[
01237                     p1_offset], lda, dumma, ldu, &evectr[evectr_offset], ldu, 
01238                     &n, &in, &work[1], &iinfo);
01239             if (iinfo != 0) {
01240                 io___55.ciunit = *nounit;
01241                 s_wsfe(&io___55);
01242                 do_fio(&c__1, "STGEVC(R,S1)", (ftnlen)12);
01243                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01244                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01245                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01246                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01247                 e_wsfe();
01248                 *info = abs(iinfo);
01249                 goto L210;
01250             }
01251 
01252             i1 = in;
01253             i__3 = i1;
01254             for (j = 1; j <= i__3; ++j) {
01255                 llwork[j] = FALSE_;
01256 /* L180: */
01257             }
01258             i__3 = n;
01259             for (j = i1 + 1; j <= i__3; ++j) {
01260                 llwork[j] = TRUE_;
01261 /* L190: */
01262             }
01263 
01264             stgevc_("R", "S", &llwork[1], &n, &s1[s1_offset], lda, &p1[
01265                     p1_offset], lda, dumma, ldu, &evectr[(i1 + 1) * 
01266                     evectr_dim1 + 1], ldu, &n, &in, &work[1], &iinfo);
01267             if (iinfo != 0) {
01268                 io___56.ciunit = *nounit;
01269                 s_wsfe(&io___56);
01270                 do_fio(&c__1, "STGEVC(R,S2)", (ftnlen)12);
01271                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01272                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01273                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01274                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01275                 e_wsfe();
01276                 *info = abs(iinfo);
01277                 goto L210;
01278             }
01279 
01280             sget52_(&c_false, &n, &s1[s1_offset], lda, &p1[p1_offset], lda, &
01281                     evectr[evectr_offset], ldu, &alphr1[1], &alphi1[1], &
01282                     beta1[1], &work[1], dumma);
01283             result[11] = dumma[0];
01284             if (dumma[1] > *thresh) {
01285                 io___57.ciunit = *nounit;
01286                 s_wsfe(&io___57);
01287                 do_fio(&c__1, "Right", (ftnlen)5);
01288                 do_fio(&c__1, "STGEVC(HOWMNY=S)", (ftnlen)16);
01289                 do_fio(&c__1, (char *)&dumma[1], (ftnlen)sizeof(real));
01290                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01291                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01292                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01293                 e_wsfe();
01294             }
01295 
01296 /*           12: Compute the right eigenvector Matrix with */
01297 /*               back transforming: */
01298 
01299             ntest = 12;
01300             result[12] = ulpinv;
01301             slacpy_("F", &n, &n, &z__[z_offset], ldu, &evectr[evectr_offset], 
01302                     ldu);
01303             stgevc_("R", "B", &llwork[1], &n, &s1[s1_offset], lda, &p1[
01304                     p1_offset], lda, dumma, ldu, &evectr[evectr_offset], ldu, 
01305                     &n, &in, &work[1], &iinfo);
01306             if (iinfo != 0) {
01307                 io___58.ciunit = *nounit;
01308                 s_wsfe(&io___58);
01309                 do_fio(&c__1, "STGEVC(R,B)", (ftnlen)11);
01310                 do_fio(&c__1, (char *)&iinfo, (ftnlen)sizeof(integer));
01311                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01312                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01313                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01314                 e_wsfe();
01315                 *info = abs(iinfo);
01316                 goto L210;
01317             }
01318 
01319             sget52_(&c_false, &n, &h__[h_offset], lda, &t[t_offset], lda, &
01320                     evectr[evectr_offset], ldu, &alphr1[1], &alphi1[1], &
01321                     beta1[1], &work[1], dumma);
01322             result[12] = dumma[0];
01323             if (dumma[1] > *thresh) {
01324                 io___59.ciunit = *nounit;
01325                 s_wsfe(&io___59);
01326                 do_fio(&c__1, "Right", (ftnlen)5);
01327                 do_fio(&c__1, "STGEVC(HOWMNY=B)", (ftnlen)16);
01328                 do_fio(&c__1, (char *)&dumma[1], (ftnlen)sizeof(real));
01329                 do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01330                 do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer));
01331                 do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(integer));
01332                 e_wsfe();
01333             }
01334 
01335 /*           Tests 13--15 are done only on request */
01336 
01337             if (*tstdif) {
01338 
01339 /*              Do Tests 13--14 */
01340 
01341                 sget51_(&c__2, &n, &s1[s1_offset], lda, &s2[s2_offset], lda, &
01342                         q[q_offset], ldu, &z__[z_offset], ldu, &work[1], &
01343                         result[13]);
01344                 sget51_(&c__2, &n, &p1[p1_offset], lda, &p2[p2_offset], lda, &
01345                         q[q_offset], ldu, &z__[z_offset], ldu, &work[1], &
01346                         result[14]);
01347 
01348 /*              Do Test 15 */
01349 
01350                 temp1 = 0.f;
01351                 temp2 = 0.f;
01352                 i__3 = n;
01353                 for (j = 1; j <= i__3; ++j) {
01354 /* Computing MAX */
01355                     r__3 = temp1, r__4 = (r__1 = alphr1[j] - alphr3[j], dabs(
01356                             r__1)) + (r__2 = alphi1[j] - alphi3[j], dabs(r__2)
01357                             );
01358                     temp1 = dmax(r__3,r__4);
01359 /* Computing MAX */
01360                     r__2 = temp2, r__3 = (r__1 = beta1[j] - beta3[j], dabs(
01361                             r__1));
01362                     temp2 = dmax(r__2,r__3);
01363 /* L200: */
01364                 }
01365 
01366 /* Computing MAX */
01367                 r__1 = safmin, r__2 = ulp * dmax(temp1,anorm);
01368                 temp1 /= dmax(r__1,r__2);
01369 /* Computing MAX */
01370                 r__1 = safmin, r__2 = ulp * dmax(temp2,bnorm);
01371                 temp2 /= dmax(r__1,r__2);
01372                 result[15] = dmax(temp1,temp2);
01373                 ntest = 15;
01374             } else {
01375                 result[13] = 0.f;
01376                 result[14] = 0.f;
01377                 result[15] = 0.f;
01378                 ntest = 12;
01379             }
01380 
01381 /*           End of Loop -- Check for RESULT(j) > THRESH */
01382 
01383 L210:
01384 
01385             ntestt += ntest;
01386 
01387 /*           Print out tests which fail. */
01388 
01389             i__3 = ntest;
01390             for (jr = 1; jr <= i__3; ++jr) {
01391                 if (result[jr] >= *thresh) {
01392 
01393 /*                 If this is the first test to fail, */
01394 /*                 print a header to the data file. */
01395 
01396                     if (nerrs == 0) {
01397                         io___62.ciunit = *nounit;
01398                         s_wsfe(&io___62);
01399                         do_fio(&c__1, "SGG", (ftnlen)3);
01400                         e_wsfe();
01401 
01402 /*                    Matrix types */
01403 
01404                         io___63.ciunit = *nounit;
01405                         s_wsfe(&io___63);
01406                         e_wsfe();
01407                         io___64.ciunit = *nounit;
01408                         s_wsfe(&io___64);
01409                         e_wsfe();
01410                         io___65.ciunit = *nounit;
01411                         s_wsfe(&io___65);
01412                         do_fio(&c__1, "Orthogonal", (ftnlen)10);
01413                         e_wsfe();
01414 
01415 /*                    Tests performed */
01416 
01417                         io___66.ciunit = *nounit;
01418                         s_wsfe(&io___66);
01419                         do_fio(&c__1, "orthogonal", (ftnlen)10);
01420                         do_fio(&c__1, "'", (ftnlen)1);
01421                         do_fio(&c__1, "transpose", (ftnlen)9);
01422                         for (j = 1; j <= 10; ++j) {
01423                             do_fio(&c__1, "'", (ftnlen)1);
01424                         }
01425                         e_wsfe();
01426 
01427                     }
01428                     ++nerrs;
01429                     if (result[jr] < 1e4f) {
01430                         io___67.ciunit = *nounit;
01431                         s_wsfe(&io___67);
01432                         do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01433                         do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer))
01434                                 ;
01435                         do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(
01436                                 integer));
01437                         do_fio(&c__1, (char *)&jr, (ftnlen)sizeof(integer));
01438                         do_fio(&c__1, (char *)&result[jr], (ftnlen)sizeof(
01439                                 real));
01440                         e_wsfe();
01441                     } else {
01442                         io___68.ciunit = *nounit;
01443                         s_wsfe(&io___68);
01444                         do_fio(&c__1, (char *)&n, (ftnlen)sizeof(integer));
01445                         do_fio(&c__1, (char *)&jtype, (ftnlen)sizeof(integer))
01446                                 ;
01447                         do_fio(&c__4, (char *)&ioldsd[0], (ftnlen)sizeof(
01448                                 integer));
01449                         do_fio(&c__1, (char *)&jr, (ftnlen)sizeof(integer));
01450                         do_fio(&c__1, (char *)&result[jr], (ftnlen)sizeof(
01451                                 real));
01452                         e_wsfe();
01453                     }
01454                 }
01455 /* L220: */
01456             }
01457 
01458 L230:
01459             ;
01460         }
01461 /* L240: */
01462     }
01463 
01464 /*     Summary */
01465 
01466     slasum_("SGG", nounit, &nerrs, &ntestt);
01467     return 0;
01468 
01469 
01470 
01471 
01472 
01473 
01474 
01475 
01476 /*     End of SCHKGG */
01477 
01478 } /* schkgg_ */


swiftnav
Author(s):
autogenerated on Sat Jun 8 2019 18:55:58