EigenLab.h
Go to the documentation of this file.
00001 // --*-  Mode: C++; c-basic-offset:4; indent-tabs-mode:t; tab-width:4 -*--
00002 // EigenLab
00003 // Version: 1.0.0
00004 // Author: Dr. Marcel Paz Goldschen-Ohm
00005 // Email:  marcel.goldschen@gmail.com
00006 // Copyright (c) 2015 by Dr. Marcel Paz Goldschen-Ohm.
00007 // Licence: MIT
00008 //----------------------------------------
00009 
00010 #ifndef EigenLab_H
00011 #define EigenLab_H
00012 
00013 #include <Eigen/Dense>
00014 #include <iomanip>
00015 #include <type_traits>
00016 #include <map>
00017 #include <sstream>
00018 #include <stdexcept>
00019 #include <string>
00020 #include <vector>
00021 
00022 // Define both DEBUG and EIGENLAB_DEBUG for step-by-step equation parsing printouts.
00023 #ifndef DEBUG
00024 //#     define DEBUG
00025 #endif
00026 
00027 #ifndef EIGENLAB_DEBUG
00028 //#     define EIGENLAB_DEBUG
00029 #endif
00030 
00031 #ifdef DEBUG
00032 #       include <iostream>
00033 #endif
00034 
00035 namespace EigenLab
00036 {
00037         //----------------------------------------
00038         // A wrapper for a matrix whose data is either stored locally or shared.
00039         //
00040         // Template typename Derived can be any dynamically sized matrix type supported by Eigen.
00041         //
00042         // !!! matrix() promises to ALWAYS return a map to the matrix data whether it's
00043         // stored locally or externally in some shared memory.
00044         //
00045         // !!! local() provides direct access to the local data, but this data is
00046         // ONLY valid when isLocal() is true. In most cases, you're best off
00047         // accessing the matrix data via matrix() instead.
00048         //----------------------------------------
00049         template <typename Derived = Eigen::MatrixXd>
00050         class Value
00051         {
00052         private:
00053                 // Local matrix data.
00054                 Derived mLocal;
00055                 
00056                 // Map to shared matrix data (map points to mLocal if the data is local).
00057                 // !!! This map promises to ALWAYS point to the matrix data whether it's
00058                 // stored locally in mLocal or externally in some shared memory.
00059                 Eigen::Map<Derived> mShared;
00060                 
00061                 // Flag indicating whether the local data is being used.
00062                 bool mIsLocal;
00063                 
00064         public:
00065                 // Access mapped data (whether its local or shared).
00066                 // !!! matrix() promises to ALWAYS return a map to the matrix data whether it's
00067                 // stored locally in mLocal or externally in some shared memory.
00068                 inline Eigen::Map<Derived> & matrix() { return mShared; }
00069                 inline const Eigen::Map<Derived> & matrix() const { return mShared; }
00070                 
00071                 // Access local data.
00072                 // !!! WARNING! This data is ONLY valid if isLocal() is true.
00073                 // !!! WARNING! If you change the local data via this method, you MUST call mapLocal() immediately afterwards.
00074                 // In most cases, you're best off accessing the matrix data via matrix() instead.
00075                 inline Derived & local() { return mLocal; }
00076                 inline const Derived & local() const { return mLocal; }
00077                 
00078                 // Is mapped data local?
00079                 inline bool isLocal() const { return mIsLocal; }
00080                 
00081                 // Set mapped data to point to local data.
00082                 inline void mapLocal() { new (& mShared) Eigen::Map<Derived>(mLocal.data(), mLocal.rows(), mLocal.cols()); mIsLocal = true; }
00083                 
00084                 //  Copy shared data to local data (if needed).
00085                 inline void copySharedToLocal() { if(!isLocal()) { mLocal = mShared; mapLocal(); } }
00086                 
00087                 // Set local data.
00088                 Value() : mLocal(1, 1), mShared(mLocal.data(), mLocal.rows(), mLocal.cols()), mIsLocal(true) {}
00089                 Value(const typename Derived::Scalar s) : mLocal(Derived::Constant(1, 1, s)), mShared(mLocal.data(), mLocal.rows(), mLocal.cols()), mIsLocal(true) {}
00090                 Value(const Derived & mat) : mLocal(mat), mShared(mLocal.data(), mLocal.rows(), mLocal.cols()), mIsLocal(true) {}
00091                 inline void setLocal(const typename Derived::Scalar s) { mLocal = Derived::Constant(1, 1, s); mapLocal(); }
00092                 inline void setLocal(const Eigen::MatrixBase<Derived> & mat) { mLocal = mat; mapLocal(); }
00093                 inline void setLocal(const Value & val) { mLocal = val.matrix(); mapLocal(); }
00094                 inline void setLocal(const typename Derived::Scalar * data, size_t rows = 1, size_t cols = 1) { setShared(data, rows, cols); copySharedToLocal(); }
00095                 inline Value & operator = (const typename Derived::Scalar s) { setLocal(s); return (* this); }
00096                 inline Value & operator = (const Derived & mat) { setLocal(mat); return (* this); }
00097                 
00098                 // Set shared data.
00099                 Value(const typename Derived::Scalar * data, size_t rows = 1, size_t cols = 1) : mShared(const_cast<typename Derived::Scalar *>(data), rows, cols), mIsLocal(false) {}
00100                 inline void setShared(const typename Derived::Scalar * data, size_t rows = 1, size_t cols = 1) { new (& mShared) Eigen::Map<Derived>(const_cast<typename Derived::Scalar *>(data), rows, cols); mIsLocal = false; }
00101                 inline void setShared(const Derived & mat) { setShared(mat.data(), mat.rows(), mat.cols()); }
00102                 inline void setShared(const Value & val) { setShared(val.matrix().data(), val.matrix().rows(), val.matrix().cols()); }
00103                 
00104                 // Set to local or shared data dependent on whether val maps its own local data or some other shared data.
00105                 Value(const Value & val) : mLocal(1, 1), mShared(mLocal.data(), mLocal.rows(), mLocal.cols()) { (* this) = val; }
00106                 inline Value & operator = (const Value & val) { if(val.isLocal()) { setLocal(val); } else { setShared(val); } return (* this); }
00107         };
00108         typedef Value<Eigen::MatrixXd> ValueXd;
00109         typedef Value<Eigen::MatrixXf> ValueXf;
00110         typedef Value<Eigen::MatrixXi> ValueXi;
00111         
00112         // check if a class has a comparison operator (ie. std::complex does not)
00113         template<typename T>
00114         struct has_operator_lt_impl
00115         {
00116                 template<class U>
00117                 static auto test(U*) -> decltype(std::declval<U>() < std::declval<U>());
00118                 template<typename>
00119                 static auto test(...) -> std::false_type;
00120                 using type = typename std::is_same<bool, decltype(test<T>(0))>::type;
00121         };
00122         template<typename T>
00123         struct has_operator_lt : has_operator_lt_impl<T>::type {};
00124         
00125         //----------------------------------------
00126         // Equation parser.
00127         //
00128         // Template typename Derived can be any dynamically sized matrix type supported by Eigen.
00129         //----------------------------------------
00130         template <typename Derived = Eigen::MatrixXd>
00131         class Parser
00132         {
00133         public:
00134                 // A map to hold named values.
00135                 typedef std::map<std::string, Value<Derived> > ValueMap;
00136                 
00137         private:
00138                 // Variables are stored in a map of named values.
00139                 ValueMap mVariables;
00140                 
00141                 // Operator symbols and function names used by the parser.
00142                 std::string mOperators1, mOperators2;
00143                 std::vector<std::string> mFunctions;
00144                 
00145                 // Expressions are parsed by first splitting them into chunks.
00146                 struct Chunk {
00147                         std::string field;
00148                         int type;
00149                         Value<Derived> value;
00150                         int row0, col0, rows, cols;
00151                         Chunk(const std::string & str = "", int t = -1, const Value<Derived> & val = Value<Derived>()) : field(str), type(t), value(val), row0(-1), col0(-1), rows(-1), cols(-1) {}
00152                 };
00153                 enum ChunkType { VALUE = 0, VARIABLE, OPERATOR, FUNCTION };
00154                 typedef std::vector<Chunk> ChunkArray;
00155                 typedef typename Derived::Index Index;
00156                 bool mCacheChunkedExpressions;
00157                 std::map<std::string, ChunkArray> mCachedChunkedExpressions;
00158                 
00159         public:
00160                 // Access to named variables.
00161                 // !!! WARNING! var(name) will create the variable name if it does not already exist.
00162                 inline ValueMap & vars() { return mVariables; }
00163                 inline Value<Derived> & var(const std::string & name) { return mVariables[name]; }
00164                 
00165                 // Check if a variable exists.
00166                 inline bool hasVar(const std::string & name) { return isVariable(name); }
00167                 
00168                 // Delete a variable.
00169                 inline void clearVar(const std::string & name) { typename ValueMap::iterator it = mVariables.find(name); if(it != mVariables.end()) mVariables.erase(it); }
00170                 
00171                 // Expression chunk caching.
00172                 inline bool cacheExpressions() const { return mCacheChunkedExpressions; }
00173                 inline void setCacheExpressions(bool b) { mCacheChunkedExpressions = b; }
00174                 inline void clearCachedExpressions() { mCachedChunkedExpressions.clear(); }
00175                 
00176                 Parser();
00177                 ~Parser() { clearCachedExpressions(); }
00178                 
00179                 // Evaluate an expression and return the result in a value wrapper.
00180                 Value<Derived> eval(const std::string & expression);
00181                 
00182         private:
00183                 void splitEquationIntoChunks(const std::string & expression, ChunkArray & chunks, std::string & code);
00184                 std::string::const_iterator findClosingBracket(const std::string & str, const std::string::const_iterator openingBracket, const char closingBracket) const;
00185                 std::vector<std::string> splitArguments(const std::string & str, const char delimeter) const;
00186                 void evalIndexRange(const std::string & str, int * first, int * last, int numIndices);
00187                 void evalMatrixExpression(const std::string & str, Value<Derived> & mat);
00188                 void evalFunction(const std::string & name, std::vector<std::string> & args, Value<Derived> & result);
00189                 bool evalFunction_1_lt(const std::string & name, Value<Derived> & arg, Value<Derived> & result, std::false_type);
00190                 bool evalFunction_1_lt(const std::string & name, Value<Derived> & arg, Value<Derived> & result, std::true_type);
00191                 bool evalFunction_2_lt(const std::string & name, Value<Derived> & arg0, Value<Derived> & arg1, Value<Derived> & result, std::false_type);
00192                 bool evalFunction_2_lt(const std::string & name, Value<Derived> & arg0, Value<Derived> & arg1, Value<Derived> & result, std::true_type);
00193                 
00194                 void evalNumericRange(const std::string & str, Value<Derived> & mat);
00195                 inline bool isVariable(const std::string & name) const { return mVariables.count(name) > 0; }
00196                 inline bool isOperator(const char c) const { return (std::find(mOperators1.begin(), mOperators1.end(), c) != mOperators1.end()); }
00197                 bool isOperator(const std::string & str) const;
00198                 inline bool isFunction(const std::string & str) const { return (std::find(mFunctions.begin(), mFunctions.end(), str) != mFunctions.end()); }
00199                 void evalIndices(ChunkArray & chunks);
00200                 void evalNegations(ChunkArray & chunks);
00201                 void evalPowers(ChunkArray & chunks);
00202                 void evalMultiplication(ChunkArray & chunks);
00203                 void evalAddition(ChunkArray & chunks);
00204                 void evalAssignment(ChunkArray & chunks);
00205 #ifdef DEBUG
00206 #       ifdef EIGENLAB_DEBUG
00207                 void printChunks(ChunkArray & chunks, size_t maxRows = 2, size_t maxCols = 2, int precision = 0);
00208                 void printVars(size_t maxRows = 2, size_t maxCols = 2, int precision = 0);
00209                 std::string textRepresentation(Value<Derived> & val, size_t maxRows = 2, size_t maxCols = 2, int precision = 0);
00210 #       endif
00211 #endif
00212                 
00213         public:
00214                 static std::string trim(const std::string & str);
00215                 static std::vector<std::string> split(const std::string & str, const char delimeter);
00216                 template <typename T> static bool isNumber(const std::string & str, T * num = 0);
00217                 template <typename T> static T stringToNumber(const std::string & str);
00218                 template <typename T> static std::string numberToString(T num, int precision = 0);
00219 #ifdef DEBUG
00220                 void test_w_lt(size_t & numFails, typename Derived::Scalar & s, Derived & a34, Derived & b34, Derived & c43, Derived & v, std::true_type);
00221                 void test_w_lt(size_t & numFails, typename Derived::Scalar & s, Derived & a34, Derived & b34, Derived & c43, Derived & v, std::false_type);
00222                 size_t test();
00223 #endif
00224         };
00225         typedef Parser<Eigen::MatrixXd> ParserXd;
00226         typedef Parser<Eigen::MatrixXf> ParserXf;
00227         typedef Parser<Eigen::MatrixXi> ParserXi;
00228         
00229         //----------------------------------------
00230         // Function definitions.
00231         //----------------------------------------
00232         template <typename Derived>
00233         Parser<Derived>::Parser() :
00234                 mOperators1("+-*/^()[]="),
00235                 mOperators2(".+.-.*./.^"),
00236                 mCacheChunkedExpressions(false)
00237         {
00238                 // Coefficient-wise operations.
00239                 mFunctions.push_back("abs");
00240                 mFunctions.push_back("sqrt");
00241                 mFunctions.push_back("square");
00242                 mFunctions.push_back("exp");
00243                 mFunctions.push_back("log");
00244                 mFunctions.push_back("log10");
00245                 mFunctions.push_back("sin");
00246                 mFunctions.push_back("cos");
00247                 mFunctions.push_back("tan");
00248                 mFunctions.push_back("asin");
00249                 mFunctions.push_back("acos");
00250 
00251                 // Matrix reduction operations.
00252                 mFunctions.push_back("trace");
00253                 mFunctions.push_back("norm");
00254                 mFunctions.push_back("size");
00255                 if (has_operator_lt<typename Derived::Scalar>::value) {
00256                         mFunctions.push_back("min");
00257                         mFunctions.push_back("minOfFinites");
00258                         mFunctions.push_back("max");
00259                         mFunctions.push_back("maxOfFinites");
00260                         mFunctions.push_back("absmax");
00261                         mFunctions.push_back("cwiseMin");
00262                         mFunctions.push_back("cwiseMax");
00263                 }
00264                 mFunctions.push_back("mean");
00265                 mFunctions.push_back("meanOfFinites");
00266                 mFunctions.push_back("sum");
00267                 mFunctions.push_back("sumOfFinites");
00268                 mFunctions.push_back("prod");
00269                 mFunctions.push_back("numberOfFinites");
00270 
00271                 // Matrix operations.
00272                 mFunctions.push_back("transpose");
00273                 mFunctions.push_back("conjugate");
00274                 mFunctions.push_back("adjoint");
00275 
00276                 // Matrix initializers.
00277                 mFunctions.push_back("zeros");
00278                 mFunctions.push_back("ones");
00279                 mFunctions.push_back("eye");
00280         }
00281         
00282         template <typename Derived>
00283         Value<Derived> Parser<Derived>::eval(const std::string & expression)
00284         {
00285 #ifdef DEBUG
00286 #       ifdef EIGENLAB_DEBUG
00287                 std::cout << "---" << std::endl;
00288                 std::cout << "EXPRESSION: " << expression << std::endl;
00289 #       endif
00290 #endif
00291                 ChunkArray chunks;
00292                 std::string code;
00293                 splitEquationIntoChunks(trim(expression), chunks, code);
00294                 evalIndices(chunks);
00295                 evalNegations(chunks);
00296                 evalPowers(chunks);
00297                 evalMultiplication(chunks);
00298                 evalAddition(chunks);
00299                 evalAssignment(chunks);
00300                 if(chunks.size() != 1)
00301                         throw std::runtime_error("Failed to reduce expression '" + expression + "' to a single value.");
00302 #ifdef DEBUG
00303 #       ifdef EIGENLAB_DEBUG
00304                 std::cout << "---" << std::endl;
00305 #       endif
00306 #endif
00307                 if(chunks[0].type == VARIABLE) {
00308                         if(!isVariable(chunks[0].field))
00309                                 throw std::runtime_error("Unknown variable '" + chunks[0].field + "'.");
00310                         return mVariables[chunks[0].field];
00311                 }
00312                 return chunks[0].value;
00313         }
00314         
00315         template <typename Derived>
00316         void Parser<Derived>::splitEquationIntoChunks(const std::string & expression, ChunkArray & chunks, std::string & code)
00317         {
00318                 if(cacheExpressions()) {
00319                         if(mCachedChunkedExpressions.count(expression) > 0) {
00320                                 chunks = mCachedChunkedExpressions.at(expression);
00321 #ifdef DEBUG
00322 #       ifdef EIGENLAB_DEBUG
00323                                 std::cout << "CACHED CHUNKS: "; printChunks(chunks); std::cout << std::endl;
00324 #       endif
00325 #endif
00326                                 return;
00327                         }
00328                 }
00329 
00330                 for(std::string::const_iterator it = expression.begin(); it != expression.end();)
00331                 {
00332                         int prevType = (chunks.size() ? chunks.back().type : -1);
00333                         char ci = (* it);
00334                         if(isspace(ci)) {
00335                                 // Ignore whitespace.
00336                                 it++;
00337                         } else if(ci == '(' && (prevType == VALUE || prevType == VARIABLE)) {
00338                                 // Index group.
00339                                 std::string::const_iterator jt = findClosingBracket(expression, it, ')');
00340                                 if(jt == expression.end())
00341                                         throw std::runtime_error("Missing closing bracket for '" + std::string(it, jt) + "'.");
00342                                 std::string field = std::string(it + 1, jt); // Outer brackets stripped.
00343                                 if(prevType == VARIABLE) {
00344                                         if(!isVariable(chunks.back().field))
00345                                                 throw std::runtime_error("Unknown variable '" + chunks.back().field + "'.");
00346                                         chunks.back().value.setShared(var(chunks.back().field));
00347                                 }
00348                                 int first, last;
00349                                 int rows = int(chunks.back().value.matrix().rows());
00350                                 int cols = int(chunks.back().value.matrix().cols());
00351                                 std::vector<std::string> args = splitArguments(field, ',');
00352                                 if(args.size() == 1) {
00353                                         if(cols == 1) {
00354                                                 evalIndexRange(args[0], & first, & last, rows);
00355                                                 chunks.back().row0 = first;
00356                                                 chunks.back().col0 = 0;
00357                                                 chunks.back().rows = last + 1 - first;//(last == -1 ? int(chunks.back().value.matrix().rows()) : last + 1) - first;
00358                                                 chunks.back().cols = 1;
00359                                         } else if(rows == 1) {
00360                                                 evalIndexRange(args[0], & first, & last, cols);
00361                                                 chunks.back().row0 = 0;
00362                                                 chunks.back().col0 = first;
00363                                                 chunks.back().rows = 1;
00364                                                 chunks.back().cols = last + 1 - first;//(last == -1 ? int(chunks.back().value.matrix().cols()) : last + 1) - first;
00365                                         } else {
00366                                                 throw std::runtime_error("Missing row or column indices for '(" + chunks.back().field + "(" + field + ")'.");
00367                                         }
00368                                 } else if(args.size() == 2) {
00369                                         evalIndexRange(args[0], & first, & last, rows);
00370                                         chunks.back().row0 = first;
00371                                         chunks.back().rows = last + 1 - first;//(last == -1 ? int(chunks.back().value.matrix().rows()) : last + 1) - first;
00372                                         evalIndexRange(args[1], & first, & last, cols);
00373                                         chunks.back().col0 = first;
00374                                         chunks.back().cols = last + 1 - first;//(last == -1 ? int(chunks.back().value.matrix().cols()) : last + 1) - first;
00375                                 } else {
00376                                         throw std::runtime_error("Invalid index expression '" + chunks.back().field + "(" + field + ")'.");
00377                                 }
00378                                 code += "i";
00379                                 it = jt + 1;
00380                         } else if(ci == '(' && prevType == FUNCTION) {
00381                                 // Function argument group.
00382                                 std::string::const_iterator jt = findClosingBracket(expression, it, ')');
00383                                 if(jt == expression.end())
00384                                         throw std::runtime_error("Missing closing bracket for '" + std::string(it, jt) + "'.");
00385                                 std::string field = std::string(it + 1, jt); // Outer brackets stripped.
00386                                 std::vector<std::string> args = splitArguments(field, ',');
00387                                 evalFunction(chunks.back().field, args, chunks.back().value);
00388                                 chunks.back().field += "(" + field + ")";
00389                                 chunks.back().type = VALUE;
00390                                 code += (chunks.back().value.matrix().size() == 1 ? "n" : "M");
00391                                 it = jt + 1;
00392                         } else if(ci == '(') {
00393                                 // Recursively evaluate group to a single value.
00394                                 std::string::const_iterator jt = findClosingBracket(expression, it, ')');
00395                                 if(jt == expression.end())
00396                                         throw std::runtime_error("Missing closing bracket for '" + std::string(it, jt) + "'.");
00397                                 std::string field = std::string(it + 1, jt); // Outer brackets stripped.
00398                                 chunks.push_back(Chunk(field, prevType = VALUE, eval(field)));
00399                                 code += (chunks.back().value.matrix().size() == 1 ? "n" : "M");
00400                                 it = jt + 1;
00401                         } else if(ci == '[') {
00402                                 // Evaluate matrix.
00403                                 if(prevType == VALUE || prevType == VARIABLE)
00404                                         throw std::runtime_error("Invalid operation '" + chunks.back().field + std::string(1, ci) + "'.");
00405                                 std::string::const_iterator jt = findClosingBracket(expression, it, ']');
00406                                 if(jt == expression.end())
00407                                         throw std::runtime_error("Missing closing bracket for '" + std::string(it, jt) + "'.");
00408                                 std::string field = std::string(it + 1, jt); // Outer brackets stripped.
00409                                 chunks.push_back(Chunk("[" + field + "]", prevType = VALUE));
00410                                 evalMatrixExpression(field, chunks.back().value);
00411                                 code += (chunks.back().value.matrix().size() == 1 ? "n" : "M");
00412                                 it = jt + 1;
00413                         } else if(it + 1 != expression.end() && isOperator(std::string(it, it + 2))) {
00414                                 // Double character operator.
00415                                 std::string field = std::string(it, it + 2);
00416                                 chunks.push_back(Chunk(field, prevType = OPERATOR));
00417                                 code += field;
00418                                 it += 2;
00419                         } else if(isOperator(ci)) {
00420                                 // Single character operator.
00421                                 std::string field = std::string(1, ci);
00422                                 chunks.push_back(Chunk(field, prevType = OPERATOR));
00423                                 code += field;
00424                                 it++;
00425                         } else {
00426                                 // Non-operator: value range, number, function, or variable name.
00427                                 std::string::const_iterator jt = it + 1;
00428                                 // accept fp-strings, ie [+-]
00429                                 unsigned char state = 1;
00430                                 for(std::string::const_iterator kt = it; state && kt != expression.end(); kt++) {
00431                                         unsigned char token;
00432                                         if (*kt == ' ') token = 0;
00433                                         else if (*kt == '+' || *kt == '-') token = 1;
00434                                         else if (isdigit(*kt)) token = 2;
00435                                         else if (*kt == '.') token = 3;
00436                                         else if (*kt == 'e' || *kt == 'E') token = 4;
00437                                         else break;
00438                                         const static char nextstate[9][5] = {{0},
00439                                                                                                                  {1, 2, 3, 4, 0},
00440                                                                                                                  {0, 0, 3, 4, 0},
00441                                                                                                                  {0, 0, 3, 5, 6},
00442                                                                                                                  {0, 0, 5, 0, 0},
00443                                                                                                                  {0, 0, 5, 0, 6},
00444                                                                                                                  {0, 7, 8, 0, 0},
00445                                                                                                                  {0, 0, 8, 0, 0},
00446                                                                                                                  {0, 0, 8, 0, 0}};
00447                                         //WARN("state=" << (int)state << " token(" << *kt << ")=" << (int)token
00448                                         //       << " nextstate = " << (int)nextstate[state][token] << "\n");
00449                                         state = nextstate[state][token];
00450                                         if (state == 8) jt = kt;
00451                                 }
00452                                 for(; jt != expression.end(); jt++) {
00453                                         if(isOperator(*jt) || (jt + 1 != expression.end() && isOperator(std::string(jt, jt + 2))))
00454                                                 break;
00455                                 }
00456                                 std::string field = trim(std::string(it, jt));
00457                                 if(prevType == VALUE || prevType == VARIABLE)
00458                                         throw std::runtime_error("Invalid operation '" + chunks.back().field + field + "'.");
00459                                 double num;
00460                                 if(field.find(":") != std::string::npos) {
00461                                         // Numeric range.
00462                                         chunks.push_back(Chunk(field, prevType = VALUE));
00463                                         evalNumericRange(field, chunks.back().value);
00464                                         code += (chunks.back().value.matrix().size() == 1 ? "n" : "M");
00465                                 } else if(isNumber<double>(field, & num)) {
00466                                         // Number.
00467                                         chunks.push_back(Chunk(field, prevType = VALUE, Value<Derived>(num)));
00468                                         code += "n";
00469                                 } else if(isVariable(field)) {
00470                                         // Local variable.
00471                                         chunks.push_back(Chunk(field, prevType = VARIABLE));
00472                                         code += (mVariables[field].matrix().size() == 1 ? "vn" : "vM");
00473                                 } else if(isFunction(field)) {
00474                                         // Function.
00475                                         chunks.push_back(Chunk(field, prevType = FUNCTION));
00476                                 } else {
00477                                         // New undefined variable.
00478                                         chunks.push_back(Chunk(field, prevType = VARIABLE));
00479                                         code += "vU";
00480                                 }
00481                                 it = jt;
00482                         }
00483                 } // it
00484 #ifdef DEBUG
00485 #       ifdef EIGENLAB_DEBUG
00486                 std::cout << "CHUNKS: "; printChunks(chunks); std::cout << std::endl;
00487                 std::cout << "CODE: " << code << std::endl;
00488 #       endif
00489 #endif
00490                 if(cacheExpressions())
00491                         mCachedChunkedExpressions[expression] = chunks;
00492         }
00493         
00494         template <typename Derived>
00495         std::string::const_iterator Parser<Derived>::findClosingBracket(const std::string & str, const std::string::const_iterator openingBracket, const char closingBracket) const
00496         {
00497                 int depth = 1;
00498                 std::string::const_iterator it = openingBracket + 1;
00499                 for(; it != str.end(); it++) {
00500                         if((*it) == (*openingBracket)) depth++;
00501                         else if((*it) == closingBracket) depth--;
00502                         if(depth == 0) return it;
00503                 }
00504                 return str.end();
00505         }
00506 
00507         template <typename Derived>
00508         std::vector<std::string> Parser<Derived>::splitArguments(const std::string & str, const char delimeter) const
00509         {
00510                 std::vector<std::string> args;
00511                 std::string::const_iterator i0 = str.begin();
00512                 for(std::string::const_iterator it = str.begin(); it != str.end(); it++) {
00513                         if((*it) == '(') it = findClosingBracket(str, it, ')');
00514                         else if((*it) == '[') it = findClosingBracket(str, it, ']');
00515                         else if((*it) == delimeter) {
00516                                 args.push_back(trim(std::string(i0, it)));
00517                                 i0 = it + 1;
00518                         }
00519                 }
00520                 args.push_back(std::string(i0, str.end()));
00521                 return args;
00522         }
00523 
00524         template <typename Derived>
00525         void Parser<Derived>::evalIndexRange(const std::string & str, int * first, int * last, int numIndices)
00526         {
00527                 if(str.empty())
00528                         throw std::runtime_error("Empty index range.");
00529                 ValueXi valuei;
00530                 ParserXi parseri;
00531                 size_t pos;
00532                 for(std::string::const_iterator it = str.begin(); it != str.end(); it++) {
00533                         if((*it) == ':') {
00534                                 std::string firstStr = trim(std::string(str.begin(), it));
00535                                 std::string lastStr = trim(std::string(it + 1, str.end()));
00536                                 if(firstStr.empty() && lastStr.empty()) {
00537                                         (* first) = 0;
00538                                         (* last) = numIndices - 1;
00539                                         return;
00540                                 }
00541                                 if(firstStr.empty() || lastStr.empty())
00542                                         throw std::runtime_error("Missing indices for '" + str + "'.");
00543                                 
00544                                 pos = firstStr.find("end");
00545                                 if(pos != std::string::npos) {
00546                                         firstStr = firstStr.substr(0, pos) + numberToString<int>(numIndices - 1) + firstStr.substr(pos + 3);
00547                                 }
00548                                 pos = lastStr.find("end");
00549                                 if(pos != std::string::npos) {
00550                                         lastStr = lastStr.substr(0, pos) + numberToString<int>(numIndices - 1) + lastStr.substr(pos + 3);
00551                                 }
00552                                 
00553                                 valuei = parseri.eval(firstStr);
00554                                 if(valuei.matrix().size() != 1)
00555                                         throw std::runtime_error("Invalid indices '" + str + "'.");
00556                                 (* first) = valuei.matrix()(0, 0);
00557                                 
00558                                 valuei = parseri.eval(lastStr);
00559                                 if(valuei.matrix().size() != 1)
00560                                         throw std::runtime_error("Invalid indices '" + str + "'.");
00561                                 (* last) = valuei.matrix()(0, 0);
00562                                 
00563                                 return;
00564                         }
00565                 }
00566                 std::string firstStr = str;
00567                 
00568                 pos = firstStr.find("end");
00569                 if(pos != std::string::npos) {
00570                         firstStr = firstStr.substr(0, pos) + numberToString<int>(numIndices - 1) + firstStr.substr(pos + 3);
00571                 }
00572                 
00573                 valuei = parseri.eval(firstStr);
00574                 if(valuei.matrix().size() != 1)
00575                         throw std::runtime_error("Invalid index '" + str + "'.");
00576                 (* first) = valuei.matrix()(0, 0);
00577                 (* last) = (* first);
00578         }
00579 
00580         template <typename Derived>
00581         void Parser<Derived>::evalMatrixExpression(const std::string & str, Value<Derived> & mat)
00582         {
00583                 // !!! Expression may NOT include outer brackets, although brackets for individual rows are OK.
00584                 std::vector<std::string> rows = splitArguments(str, ';');
00585                 std::vector<std::vector<typename Derived::Scalar> > temp;
00586                 Value<Derived> submatrix;
00587                 size_t row0 = 0, col0 = 0, nrows = 0, ncols = 0;
00588                 size_t pos;
00589                 for(size_t i = 0; i < rows.size(); i++) {
00590                         // Strip row brackets if they exist.
00591                         if(rows[i][0] == '[' && rows[i].back() == ']') rows[i] = rows[i].substr(1, int(rows[i].size()) - 2);
00592                         std::vector<std::string> cols = splitArguments(rows[i], ',');
00593                         col0 = 0;
00594                         ncols = 0;
00595                         for(size_t j = 0; j < cols.size(); j++) {
00596                                 pos = cols[j].find(":");
00597                                 if(pos != std::string::npos) {
00598                                         std::string firstStr = cols[j].substr(0, pos);
00599                                         std::string lastStr = cols[j].substr(pos + 1);
00600                                         pos = lastStr.find(":");
00601                                         if(pos != std::string::npos) {
00602                                                 std::string stepStr = lastStr.substr(0, pos);
00603                                                 lastStr = lastStr.substr(pos + 1);
00604                                                 if(lastStr.find(":") != std::string::npos)
00605                                                         throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Invalid range '" + cols[j] + "'.");
00606                                                 // first:step:last
00607                                                 Value<Derived> first = eval(firstStr);
00608                                                 Value<Derived> step = eval(stepStr);
00609                                                 Value<Derived> last = eval(lastStr);
00610                                                 if(first.matrix().size() != 1 || step.matrix().size() != 1 || last.matrix().size() != 1)
00611                                                         throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Invalid range '" + cols[j] + "'.");
00612                                                 typename Derived::RealScalar sfirst = std::real(first.matrix()(0));
00613                                                 typename Derived::RealScalar sstep = std::real(step.matrix()(0));
00614                                                 typename Derived::RealScalar slast = std::real(last.matrix()(0));
00615                                                 if(sfirst == slast) {
00616                                                         submatrix.local().setConstant(1, 1, sfirst);
00617                                                         submatrix.mapLocal();
00618                                                 } else if((slast - sfirst >= 0 && sstep > 0) || (slast - sfirst <= 0 && sstep < 0)) {
00619                                                         int n = floor((slast - sfirst) / sstep) + 1;
00620                                                         submatrix.local().resize(1, n);
00621                                                         for(int k = 0; k < n; ++k)
00622                                                                 submatrix.local()(0, k) = sfirst + k * sstep;
00623                                                         submatrix.mapLocal();
00624                                                 } else {
00625                                                         throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Invalid range '" + cols[j] + "'.");
00626                                                 }
00627                                         } else {
00628                                                 // first:last => first:1:last
00629                                                 Value<Derived> first = eval(firstStr);
00630                                                 Value<Derived> last = eval(lastStr);
00631                                                 if(first.matrix().size() != 1 || last.matrix().size() != 1)
00632                                                         throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Invalid range '" + cols[j] + "'.");
00633                                                 typename Derived::RealScalar sfirst = std::real(first.matrix()(0));
00634                                                 typename Derived::RealScalar slast = std::real(last.matrix()(0));
00635                                                 if(sfirst == slast) {
00636                                                         submatrix.local().setConstant(1, 1, sfirst);
00637                                                         submatrix.mapLocal();
00638                                                 } else if(slast - sfirst >= 0) {
00639                                                         int n = floor(slast - sfirst) + 1;
00640                                                         submatrix.local().resize(1, n);
00641                                                         for(int k = 0; k < n; ++k)
00642                                                                 submatrix.local()(0, k) = sfirst + k;
00643                                                         submatrix.mapLocal();
00644                                                 } else {
00645                                                         throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Invalid range '" + cols[j] + "'.");
00646                                                 }
00647                                         }
00648                                 } else {
00649                                         submatrix = eval(cols[j]);
00650                                 }
00651                                 if(j > 0 && size_t(submatrix.matrix().cols()) != nrows)
00652                                         throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Successive column entries '" + cols[int(j) - 1] + "' and '" + cols[j] + "' do not have the same number of rows.");
00653                                 nrows = submatrix.matrix().rows();
00654                                 ncols += submatrix.matrix().cols();
00655                                 temp.resize(row0 + submatrix.matrix().rows());
00656                                 for(size_t row = 0; row < size_t(submatrix.matrix().rows()); row++) {
00657                                         temp[row0 + row].resize(col0 + submatrix.matrix().cols());
00658                                         for(size_t col = 0; col < size_t(submatrix.matrix().cols()); col++)
00659                                                 temp[row0 + row][col0 + col] = submatrix.matrix()(row, col);
00660                                 }
00661                                 col0 += submatrix.matrix().cols();
00662                         }
00663                         if(row0 > 0 && ncols != temp[int(row0) - 1].size())
00664                                 throw std::runtime_error("Invalid matrix definition '[" + str + "]'. Successive row entries '" + rows[int(i) - 1] + "' and '" + rows[i] + "' do not have the same number of columns.");
00665                         row0 += nrows;
00666                 }
00667                 nrows = temp.size();
00668                 if(nrows == 0) return;
00669                 ncols = temp[0].size();
00670                 mat.setLocal(Derived(nrows, ncols));
00671                 for(size_t row = 0; row < nrows; row++) {
00672                         for(size_t col = 0; col < ncols; col++)
00673                                 mat.matrix()(row, col) = temp[row][col];
00674                 }
00675                 mat.mapLocal();
00676         }
00677 
00678         template <typename Derived>
00679         bool Parser<Derived>::evalFunction_1_lt(const std::string & name, Value<Derived> & arg, Value<Derived> & result, std::true_type)
00680         {
00681                 if(name == "min") {
00682                         result.setLocal(arg.matrix().minCoeff());
00683                         return true;
00684     } else if(name == "minOfFinites") {
00685       result.setLocal(arg.matrix().minCoeffOfFinites());
00686       return true;
00687                 } else if(name == "max") {
00688                         result.setLocal(arg.matrix().maxCoeff());
00689                         return true;
00690                 } else if(name == "maxOfFinites") {
00691                         result.setLocal(arg.matrix().maxCoeffOfFinites());
00692                         return true;
00693                 } else if(name == "absmax") {
00694                         typename Derived::Scalar minimum = arg.matrix().minCoeff();
00695                         typename Derived::Scalar maximum = arg.matrix().maxCoeff();
00696                         result.setLocal(std::abs(maximum) >= std::abs(minimum) ? maximum : minimum);
00697                         return true;
00698                 }
00699                 return false;
00700         }
00701 
00702         template <typename Derived>
00703         bool Parser<Derived>::evalFunction_1_lt(const std::string &/*name*/, Value<Derived> &/*arg0*/, Value<Derived> &/*result*/, std::false_type)
00704         {
00705                 return false;
00706         }
00707 
00708         template <typename Derived>
00709         bool Parser<Derived>::evalFunction_2_lt(const std::string & name, Value<Derived> & arg0, Value<Derived> & arg1, Value<Derived> & result, std::true_type)
00710         {
00711                 if(name == "min") {
00712                         if(arg1.matrix().size() != 1)
00713                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00714                         int dim = floor(std::real(arg1.matrix()(0, 0)));
00715                         if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00716                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00717                         if(dim == 0) {
00718                                 result.local() = arg0.matrix().colwise().minCoeff();
00719                                 result.mapLocal();
00720                                 return true;
00721                         } else if(dim == 1) {
00722                                 result.local() = arg0.matrix().rowwise().minCoeff();
00723                                 result.mapLocal();
00724                                 return true;
00725                         }
00726                 } else if(name == "max") {
00727                         if(arg1.matrix().size() != 1)
00728                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00729                         int dim = floor(std::real(arg1.matrix()(0, 0)));
00730                         if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00731                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00732                         if(dim == 0) {
00733                                 result.local() = arg0.matrix().colwise().maxCoeff();
00734                                 result.mapLocal();
00735                                 return true;
00736                         } else if(dim == 1) {
00737                                 result.local() = arg0.matrix().rowwise().maxCoeff();
00738                                 result.mapLocal();
00739                                 return true;
00740                         }
00741                 } else if(name == "absmax") {
00742                         if(arg1.matrix().size() != 1)
00743                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00744                         int dim = floor(std::real(arg1.matrix()(0, 0)));
00745                         if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00746                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00747                         if(dim == 0) {
00748                                 result.local() = arg0.matrix().colwise().maxCoeff();
00749                                 result.mapLocal();
00750                                 Derived minimum = arg0.matrix().colwise().minCoeff();
00751                                 for(size_t i = 0; i < size_t(result.matrix().size()); i++) {
00752                                         if(std::abs(result.matrix()(i)) < std::abs(minimum(i)))
00753                                                 result.matrix()(i) = minimum(i);
00754                                 }
00755                                 return true;
00756                         } else if(dim == 1) {
00757                                 result.local() = arg0.matrix().rowwise().maxCoeff();
00758                                 result.mapLocal();
00759                                 Derived minimum = arg0.matrix().rowwise().minCoeff();
00760                                 for(size_t i = 0; i < size_t(result.matrix().size()); i++) {
00761                                         if(std::abs(result.matrix()(i)) < std::abs(minimum(i)))
00762                                                 result.matrix()(i) = minimum(i);
00763                                 }
00764                                 return true;
00765                         }
00766                 } else if (name == "cwiseMin") {
00767                         if (arg1.matrix().size() == 1) {
00768                                 typename Derived::Scalar arg1scalar = arg1.matrix()(0, 0);
00769                                 Derived arg1matrix = Derived::Constant(arg0.matrix().rows(), arg0.matrix().cols(), arg1scalar);
00770                                 result.local() = arg0.matrix().cwiseMin(arg1matrix);
00771                                 result.mapLocal();
00772                                 return true;
00773                         } else if (arg0.matrix().cols() == arg1.matrix().cols() && arg0.matrix().rows() == arg1.matrix().rows()) {
00774                                 result.local() = arg0.matrix().cwiseMin(arg1.matrix());
00775                                 result.mapLocal();
00776                                 return true;
00777                         } else {
00778                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00779                         }
00780                 } else if (name == "cwiseMax") {
00781                         if (arg1.matrix().size() == 1) {
00782                                 typename Derived::Scalar arg1scalar = arg1.matrix()(0, 0);
00783                                 Derived arg1matrix = Derived::Constant(arg0.matrix().rows(), arg0.matrix().cols(), arg1scalar);
00784                                 result.local() = arg0.matrix().cwiseMax(arg1matrix);
00785                                 result.mapLocal();
00786                                 return true;
00787                         } else if (arg0.matrix().cols() == arg1.matrix().cols() && arg0.matrix().rows() == arg1.matrix().rows()) {
00788                                 result.local() = arg0.matrix().cwiseMax(arg1.matrix());
00789                                 result.mapLocal();
00790                                 return true;
00791                         } else {
00792                                 throw std::runtime_error("Invalid dimension argument for function '" + name + "(...)'.");
00793                         }
00794                 }
00795                 return false;
00796         }
00797 
00798         template <typename Derived>
00799         bool Parser<Derived>::evalFunction_2_lt(const std::string &/*name*/, Value<Derived> &/*arg0*/, Value<Derived> &/*arg1*/, Value<Derived> &/*result*/, std::false_type)
00800         {
00801                 return false;
00802         }
00803         
00804         template <typename Derived>
00805         void Parser<Derived>::evalFunction(const std::string & name, std::vector<std::string> & args, Value<Derived> & result)
00806         {
00807                 if(args.size() == 1) {
00808                         Value<Derived> arg = eval(args[0]);
00809                         if(name == "abs") {
00810                                 result.local() = arg.matrix().array().abs().template cast<typename Derived::Scalar>();
00811                                 result.mapLocal();
00812                                 return;
00813                         } else if(name == "sqrt") {
00814                                 result.local() = arg.matrix().array().sqrt();
00815                                 result.mapLocal();
00816                                 return;
00817                         } else if(name == "square") {
00818                                 result.local() = arg.matrix().array().square();
00819                                 result.mapLocal();
00820                                 return;
00821                         } else if(name == "exp") {
00822                                 result.local() = arg.matrix().array().exp();
00823                                 result.mapLocal();
00824                                 return;
00825                         } else if(name == "log") {
00826                                 result.local() = arg.matrix().array().log();
00827                                 result.mapLocal();
00828                                 return;
00829                         } else if(name == "log10") {
00830                 result.local() = arg.matrix().array().log();
00831                 result.local() *= (1.0 / log(10));
00832                                 result.mapLocal();
00833                                 return;
00834                         } else if(name == "sin") {
00835                                 result.local() = arg.matrix().array().sin();
00836                                 result.mapLocal();
00837                                 return;
00838                         } else if(name == "cos") {
00839                                 result.local() = arg.matrix().array().cos();
00840                                 result.mapLocal();
00841                                 return;
00842                         } else if(name == "tan") {
00843                                 result.local() = arg.matrix().array().tan();
00844                                 result.mapLocal();
00845                                 return;
00846                         } else if(name == "acos") {
00847                                 result.local() = arg.matrix().array().acos();
00848                                 result.mapLocal();
00849                                 return;
00850                         } else if(name == "asin") {
00851                                 result.local() = arg.matrix().array().asin();
00852                                 result.mapLocal();
00853                                 return;
00854                         } else if(name == "trace") {
00855                                 result.setLocal(arg.matrix().trace());
00856                                 return;
00857                         } else if(name == "norm") {
00858                                 result.setLocal(arg.matrix().norm());
00859                                 return;
00860                         } else if (evalFunction_1_lt(name, arg, result, has_operator_lt<typename Derived::Scalar>())) {
00861                                 return;
00862                         } else if(name == "mean") {
00863                                 result.setLocal(arg.matrix().mean());
00864                                 return;
00865       } else if(name == "meanOfFinites") {
00866         result.setLocal(arg.matrix().meanOfFinites());
00867         return;
00868                         } else if(name == "sum") {
00869                                 result.setLocal(arg.matrix().sum());
00870                                 return;
00871                         } else if(name == "sumOfFinites") {
00872                                 result.setLocal(arg.matrix().sumOfFinites());
00873                                 return;
00874                         } else if(name == "prod") {
00875                                 result.setLocal(arg.matrix().prod());
00876                                 return;
00877                         } else if(name == "numberOfFinites") {
00878                                 result.setLocal(arg.matrix().numberOfFinites());
00879                                 return;
00880                         } else if(name == "transpose") {
00881                                 result.local() = arg.matrix().transpose();
00882                                 result.mapLocal();
00883                                 return;
00884                         } else if(name == "conjugate") {
00885                                 result.local() = arg.matrix().conjugate();
00886                                 result.mapLocal();
00887                                 return;
00888                         } else if(name == "adjoint") {
00889                                 result.local() = arg.matrix().adjoint();
00890                                 result.mapLocal();
00891                                 return;
00892             } else if(name == "zeros") {
00893                 if(arg.matrix().size() != 1)
00894                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + ")'.");
00895                 int N = floor(std::real(arg.matrix()(0, 0)));
00896                 if(N <= 0 || N != std::real(arg.matrix()(0, 0)))
00897                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + ")'.");
00898                 result.local() = Derived::Zero(N, N);
00899                 result.mapLocal();
00900                 return;
00901             } else if(name == "ones") {
00902                 if(arg.matrix().size() != 1)
00903                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + ")'.");
00904                 int N = floor(std::real(arg.matrix()(0, 0)));
00905                 if(N <= 0 || N != std::real(arg.matrix()(0, 0)))
00906                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + ")'.");
00907                 result.local() = Derived::Ones(N, N);
00908                 result.mapLocal();
00909                 return;
00910             } else if(name == "eye") {
00911                 if(arg.matrix().size() != 1)
00912                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + ")'.");
00913                 int N = floor(std::real(arg.matrix()(0, 0)));
00914                 if(N <= 0 || N != std::real(arg.matrix()(0, 0)))
00915                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + ")'.");
00916                 result.local() = Derived::Identity(N, N);
00917                 result.mapLocal();
00918                 return;
00919                         }
00920                         else {
00921                                 throw std::runtime_error("Invalid function '" + name + "(" + args[0] + ")'.");
00922                         }
00923                 } else if(args.size() == 2) {
00924                         Value<Derived> arg0 = eval(args[0]);
00925                         Value<Derived> arg1 = eval(args[1]);
00926             if(name == "size") {
00927                 if(arg1.matrix().size() != 1)
00928                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00929                 int dim = floor(std::real(arg1.matrix()(0, 0)));
00930                 if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00931                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00932                                 if(dim == 0) {
00933                                         result.setLocal((typename Derived::Scalar) arg0.matrix().rows());
00934                                         return;
00935                                 } else if(dim == 1) {
00936                                         result.setLocal((typename Derived::Scalar) arg0.matrix().cols());
00937                                         return;
00938                 }
00939                         } else if (evalFunction_2_lt(name, arg0, arg1, result, has_operator_lt<typename Derived::Scalar>())) {
00940                                 return;
00941                         } else if(name == "mean") {
00942                 if(arg1.matrix().size() != 1)
00943                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00944                 int dim = floor(std::real(arg1.matrix()(0, 0)));
00945                 if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00946                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00947                                 if(dim == 0) {
00948                                         result.local() = arg0.matrix().colwise().mean();
00949                                         result.mapLocal();
00950                                         return;
00951                                 } else if(dim == 1) {
00952                                         result.local() = arg0.matrix().rowwise().mean();
00953                                         result.mapLocal();
00954                                         return;
00955                                 }
00956             } else if(name == "sum") {
00957                 if(arg1.matrix().size() != 1)
00958                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00959                 int dim = floor(std::real(arg1.matrix()(0, 0)));
00960                 if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00961                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00962                                 if(dim == 0) {
00963                                         result.local() = arg0.matrix().colwise().sum();
00964                                         result.mapLocal();
00965                                         return;
00966                                 } else if(dim == 1) {
00967                                         result.local() = arg0.matrix().rowwise().sum();
00968                                         result.mapLocal();
00969                                         return;
00970                                 }
00971             } else if(name == "prod") {
00972                 if(arg1.matrix().size() != 1)
00973                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00974                 int dim = floor(std::real(arg1.matrix()(0, 0)));
00975                 if((dim != 0 && dim != 1) || dim != std::real(arg1.matrix()(0, 0)))
00976                     throw std::runtime_error("Invalid dimension argument for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00977                                 if(dim == 0) {
00978                                         result.local() = arg0.matrix().colwise().prod();
00979                                         result.mapLocal();
00980                                         return;
00981                                 } else if(dim == 1) {
00982                                         result.local() = arg0.matrix().rowwise().prod();
00983                                         result.mapLocal();
00984                                         return;
00985                 }
00986             } else if(name == "zeros") {
00987                 if((arg0.matrix().size() != 1) || (arg1.matrix().size() != 1))
00988                     throw std::runtime_error("Invalid dimension arguments for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00989                 int rows = floor(std::real(arg0.matrix()(0, 0)));
00990                 int cols = floor(std::real(arg1.matrix()(0, 0)));
00991                 if(rows <= 0 || cols <= 0 || rows != std::real(arg0.matrix()(0, 0)) || cols != std::real(arg1.matrix()(0, 0)))
00992                     throw std::runtime_error("Invalid dimension arguments for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00993                 result.local() = Derived::Zero(rows, cols);
00994                 result.mapLocal();
00995                 return;
00996             } else if(name == "ones") {
00997                 if((arg0.matrix().size() != 1) || (arg1.matrix().size() != 1))
00998                     throw std::runtime_error("Invalid dimension arguments for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
00999                 int rows = floor(std::real(arg0.matrix()(0, 0)));
01000                 int cols = floor(std::real(arg1.matrix()(0, 0)));
01001                 if(rows <= 0 || cols <= 0 || rows != std::real(arg0.matrix()(0, 0)) || cols != std::real(arg1.matrix()(0, 0)))
01002                     throw std::runtime_error("Invalid dimension arguments for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
01003                 result.local() = Derived::Ones(rows, cols);
01004                 result.mapLocal();
01005                 return;
01006             } else if(name == "eye") {
01007                 if((arg0.matrix().size() != 1) || (arg1.matrix().size() != 1))
01008                     throw std::runtime_error("Invalid dimension arguments for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
01009                 int rows = floor(std::real(arg0.matrix()(0, 0)));
01010                 int cols = floor(std::real(arg1.matrix()(0, 0)));
01011                 if(rows <= 0 || cols <= 0 || rows != std::real(arg0.matrix()(0, 0)) || cols != std::real(arg1.matrix()(0, 0)))
01012                     throw std::runtime_error("Invalid dimension arguments for function '" + name + "(" + args[0] + "," + args[1] + ")'.");
01013                 result.local() = Derived::Identity(rows, cols);
01014                 result.mapLocal();
01015                 return;
01016                         } else {
01017                                 throw std::runtime_error("Invalid function '" + name + "(" + args[0] + "," + args[1] + ")'.");
01018                         }
01019                 }
01020                 std::string argsStr = "(";
01021                 for(size_t i = 0; i < args.size(); i++) {
01022                         if(i > 0) argsStr += ",";
01023                         argsStr += args[i];
01024                 }
01025                 argsStr += ")";
01026                 throw std::runtime_error("Invalid function/arguments for '" + name + argsStr + "'.");
01027         }
01028         
01029         template <typename Derived>
01030         void Parser<Derived>::evalNumericRange(const std::string & str, Value<Derived> & mat)
01031         {
01032                 size_t pos = str.find(":");
01033                 if(pos == std::string::npos)
01034                         throw std::runtime_error("Invalid numeric range '" + str + "'.");
01035                 size_t pos2 = str.substr(pos + 1).find(":");
01036                 if(pos2 == std::string::npos) {
01037                         // first:last
01038                         std::string firstStr = str.substr(0, pos);
01039                         std::string lastStr = str.substr(pos + 1);
01040                         Value<Derived> first = eval(firstStr);
01041                         Value<Derived> last = eval(lastStr);
01042                         if(first.matrix().size() != 1 || last.matrix().size() != 1)
01043                                 throw std::runtime_error("Invalid numeric range '" + str + "'.");
01044                         typename Derived::RealScalar sfirst = std::real(first.matrix()(0,0));
01045                         typename Derived::RealScalar slast = std::real(last.matrix()(0,0));
01046                         if(sfirst > slast)
01047                                 throw std::runtime_error("Invalid numeric range '" + str + "'. Must not reverse.");
01048                         int n = 1 + floor(slast - sfirst);
01049                         mat.local().resize(1, n);
01050                         for(int i = 0; i < n; i++)
01051                                 mat.local()(0, i) = sfirst + i;
01052                         mat.mapLocal();
01053                 } else {
01054                         // first:step:last
01055                         pos2 += pos + 1;
01056                         std::string firstStr = str.substr(0, pos);
01057                         std::string stepStr = str.substr(pos + 1, pos2 - pos - 1);
01058                         std::string lastStr = str.substr(pos2 + 1);
01059                         Value<Derived> first = eval(firstStr);
01060                         Value<Derived> step = eval(stepStr);
01061                         Value<Derived> last = eval(lastStr);
01062                         if(first.matrix().size() != 1 || step.matrix().size() != 1 || last.matrix().size() != 1)
01063                                 throw std::runtime_error("Invalid numeric range '" + str + "'.");
01064                         typename Derived::RealScalar sfirst = std::real(first.matrix()(0, 0));
01065                         typename Derived::RealScalar sstep = std::real(step.matrix()(0, 0));
01066                         typename Derived::RealScalar slast = std::real(last.matrix()(0, 0));
01067                         if(sfirst == slast) {
01068                                 mat = sfirst;
01069                         } else if(sfirst < slast && sstep > 0) {
01070                                 int n = 1 + floor((slast - sfirst) / sstep);
01071                                 mat.local().resize(1, n);
01072                                 for(int i = 0; i < n; i++)
01073                                         mat.local()(0, i) = sfirst + i * sstep;
01074                                 mat.mapLocal();
01075                         } else if(sfirst > slast && sstep < 0) {
01076                                 int n = 1 + floor((slast - sfirst) / sstep);
01077                                 mat.local().resize(1, n);
01078                                 for(int i = 0; i < n; i++)
01079                                         mat.local()(0, i) = sfirst + i * sstep;
01080                                 mat.mapLocal();
01081                         } else {
01082                                 throw std::runtime_error("Invalid numeric range '" + str + "'.");
01083                         }
01084                 }
01085         }
01086         
01087         template <typename Derived>
01088         bool Parser<Derived>::isOperator(const std::string & str) const
01089         {
01090                 if(str.size() == 1)
01091                         return isOperator(str[0]);
01092                 else if(str.size() == 2) {
01093                         size_t pos = mOperators2.find(str);
01094                         return (pos != std::string::npos && pos % 2 == 0);
01095                 }
01096                 return false;
01097         }
01098         
01099         template <typename Derived>
01100         void Parser<Derived>::evalIndices(ChunkArray & chunks)
01101         {
01102 #ifdef DEBUG
01103 #       ifdef EIGENLAB_DEBUG
01104                 bool operationPerformed = false;
01105 #       endif
01106 #endif
01107                 for(typename ChunkArray::iterator it = chunks.begin(); it != chunks.end(); it++) {
01108                         if(it->row0 != -1 && (it->type == VALUE || (it->type == VARIABLE && (it + 1 == chunks.end() || (it + 1)->type != OPERATOR || (it + 1)->field != "=")))) {
01109                                 if(it->type == VALUE) {
01110                                         Derived temp = it->value.local().block(it->row0, it->col0, it->rows, it->cols);
01111                                         it->value.local() = temp;
01112                                         it->value.mapLocal();
01113                                 } else { //if(it->type == VARIABLE) {
01114                                         if(!isVariable(it->field))
01115                                                 throw std::runtime_error("Attempted indexing into uninitialized variable '" + it->field + "'.");
01116                                         it->value.local() = mVariables[it->field].matrix().block(it->row0, it->col0, it->rows, it->cols);
01117                                         it->value.mapLocal();
01118                                         it->type = VALUE;
01119                                 }
01120                                 it->row0 = -1;
01121                                 it->col0 = -1;
01122                                 it->rows = -1;
01123                                 it->cols = -1;
01124 #ifdef DEBUG
01125 #       ifdef EIGENLAB_DEBUG
01126                                 operationPerformed = true;
01127 #       endif
01128 #endif
01129                         }
01130                 }
01131 #ifdef DEBUG
01132 #       ifdef EIGENLAB_DEBUG
01133                 if(operationPerformed) { std::cout << "i: "; printChunks(chunks); std::cout << std::endl; }
01134 #       endif
01135 #endif
01136         }
01137         
01138         template <typename Derived>
01139         void Parser<Derived>::evalNegations(ChunkArray & chunks)
01140         {
01141 #ifdef DEBUG
01142 #       ifdef EIGENLAB_DEBUG
01143                 bool operationPerformed = false;
01144 #       endif
01145 #endif
01146                 if(chunks.size() < 2) return;
01147                 typename ChunkArray::iterator lhs = chunks.begin(), op = chunks.begin(), rhs = op + 1;
01148                 for(; lhs != chunks.end() && op != chunks.end() && rhs != chunks.end();) {
01149                         if(op->type == OPERATOR && op->field == "-" && (op == chunks.begin() || (lhs->type != VALUE && lhs->type != VARIABLE)) && (rhs->type == VALUE || rhs->type == VARIABLE)) {
01150                                 if(rhs->type == VALUE)
01151                                         rhs->value.matrix().array() *= -1;
01152                                 else if(rhs->type == VARIABLE) {
01153                                         if(!isVariable(rhs->field))
01154                                                 throw std::runtime_error("Attempted operation '" + op->field + rhs->field + "' on uninitialized variable '" + rhs->field + "'.");
01155                                         rhs->value.local() = mVariables[rhs->field].matrix().array() * -1;
01156                                         rhs->value.mapLocal();
01157                                         rhs->type = VALUE;
01158                                 }
01159                                 lhs = chunks.erase(op);
01160                                 op = (lhs != chunks.end()) ? lhs + 1 : lhs;
01161                                 rhs = (op != chunks.end()) ? op + 1 : op;
01162 #ifdef DEBUG
01163 #       ifdef EIGENLAB_DEBUG
01164                                 operationPerformed = true;
01165 #       endif
01166 #endif
01167                         } else {
01168                                 lhs = op;
01169                                 op = rhs;
01170                                 rhs++;
01171                         }
01172                 }
01173 #ifdef DEBUG
01174 #       ifdef EIGENLAB_DEBUG
01175                 if(operationPerformed) { std::cout << "-: "; printChunks(chunks); std::cout << std::endl; }
01176 #       endif
01177 #endif
01178         }
01179 
01180         template <typename Derived>
01181         void Parser<Derived>::evalPowers(ChunkArray & chunks)
01182         {
01183 #ifdef DEBUG
01184 #       ifdef EIGENLAB_DEBUG
01185                 bool operationPerformed = false;
01186 #       endif
01187 #endif
01188                 if(chunks.size() < 3) return;
01189                 typename ChunkArray::iterator lhs = chunks.begin(), op = lhs + 1, rhs = op + 1;
01190                 for(; lhs != chunks.end() && op != chunks.end() && rhs != chunks.end();) {
01191                         if((op->type == OPERATOR) && (op->field == "^" || op->field == ".^")) {
01192                                 if(lhs->type == VARIABLE) {
01193                                         if(!isVariable(lhs->field))
01194                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + lhs->field + "'.");
01195                                         lhs->value.setShared(mVariables[lhs->field]);
01196                                 }
01197                                 if(rhs->type == VARIABLE) {
01198                                         if(!isVariable(rhs->field))
01199                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + rhs->field + "'.");
01200                                         rhs->value.setShared(mVariables[rhs->field]);
01201                                 }
01202                                 if(rhs->value.matrix().size() == 1) {
01203                                         lhs->value.local() = lhs->value.matrix().array().pow(rhs->value.matrix()(0, 0));
01204                                         lhs->value.mapLocal();
01205                                         lhs->type = VALUE;
01206                                 } else if(lhs->value.matrix().size() == 1) {
01207                                         typename Derived::Scalar temp = lhs->value.matrix()(0, 0);
01208                                         lhs->value.local().resize(rhs->value.matrix().rows(), rhs->value.matrix().cols());
01209                                         for(size_t row = 0; row < size_t(rhs->value.matrix().rows()); row++) {
01210                                                 for(size_t col = 0; col < size_t(rhs->value.matrix().cols()); col++)
01211                                                         lhs->value.local()(row, col) = pow(temp, rhs->value.matrix()(row, col));
01212                                         }
01213                                         lhs->value.mapLocal();
01214                                         lhs->type = VALUE;
01215                                 } else if(op->field == ".^" && lhs->value.matrix().rows() == rhs->value.matrix().rows() && lhs->value.matrix().cols() == rhs->value.matrix().cols()) {
01216                                         lhs->value.local().resize(rhs->value.matrix().rows(), rhs->value.matrix().cols());
01217                                         for(size_t row = 0; row < size_t(rhs->value.matrix().rows()); row++) {
01218                                                 for(size_t col = 0; col < size_t(rhs->value.matrix().cols()); col++)
01219                                                         lhs->value.local()(row, col) = pow(lhs->value.matrix()(row, col), rhs->value.matrix()(row, col));
01220                                         }
01221                                         lhs->value.mapLocal();
01222                                         lhs->type = VALUE;
01223                                 } else {
01224                                         throw std::runtime_error("Invalid operand dimensions for operation '" + lhs->field + op->field + rhs->field + "'.");
01225                                 }
01226                                 chunks.erase(op, rhs + 1);
01227                                 op = lhs + 1;
01228                                 rhs = (op != chunks.end()) ? op + 1 : op;
01229 #ifdef DEBUG
01230 #       ifdef EIGENLAB_DEBUG
01231                                 operationPerformed = true;
01232 #       endif
01233 #endif
01234                         } else {
01235                                 lhs = op;
01236                                 op = rhs;
01237                                 rhs++;
01238                         }
01239                 }
01240 #ifdef DEBUG
01241 #       ifdef EIGENLAB_DEBUG
01242                 if(operationPerformed) { std::cout << "^: "; printChunks(chunks); std::cout << std::endl; }
01243 #       endif
01244 #endif
01245         }
01246 
01247         template <typename Derived>
01248         void Parser<Derived>::evalMultiplication(ChunkArray & chunks)
01249         {
01250 #ifdef DEBUG
01251 #       ifdef EIGENLAB_DEBUG
01252                 bool operationPerformed = false;
01253 #       endif
01254 #endif
01255                 if(chunks.size() < 3) return;
01256                 typename ChunkArray::iterator lhs = chunks.begin(), op = lhs + 1, rhs = op + 1;
01257                 for(; lhs != chunks.end() && op != chunks.end() && rhs != chunks.end();) {
01258                         if((op->type == OPERATOR) && (op->field == "*" || op->field == "/" || op->field == ".*" || op->field == "./")) {
01259                                 if(lhs->type == VARIABLE) {
01260                                         if(!isVariable(lhs->field))
01261                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + lhs->field + "'.");
01262                                         lhs->value.setShared(mVariables[lhs->field]);
01263                                 }
01264                                 if(rhs->type == VARIABLE) {
01265                                         if(!isVariable(rhs->field))
01266                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + rhs->field + "'.");
01267                                         rhs->value.setShared(mVariables[rhs->field]);
01268                                 }
01269                                 if(rhs->value.matrix().size() == 1) {
01270                                         if(lhs->value.isLocal()) {
01271                                                 if(op->field == "*" || op->field == ".*")
01272                                                         lhs->value.local().array() *= rhs->value.matrix()(0, 0);
01273                                                 else // if(op->field == "/" || op->field == "./")
01274                                                         lhs->value.local().array() /= rhs->value.matrix()(0, 0);
01275                                         } else {
01276                                                 if(op->field == "*" || op->field == ".*")
01277                                                         lhs->value.local() = lhs->value.matrix().array() * rhs->value.matrix()(0, 0);
01278                                                 else // if(op->field == "/" || op->field == "./")
01279                                                         lhs->value.local() = lhs->value.matrix().array() / rhs->value.matrix()(0, 0);
01280                                                 lhs->value.mapLocal();
01281                                                 lhs->type = VALUE;
01282                                         }
01283                                 } else if(lhs->value.matrix().size() == 1) {
01284                                         typename Derived::Scalar temp = lhs->value.matrix()(0, 0);
01285                                         if(op->field == "*" || op->field == ".*")
01286                                                 lhs->value.local() = rhs->value.matrix().array() * temp;
01287                                         else // if(op->field == "/" || op->field == "./")
01288                                                 lhs->value.local() = Derived::Constant(rhs->value.matrix().rows(), rhs->value.matrix().cols(), temp).array() / rhs->value.matrix().array();
01289                                         lhs->value.mapLocal();
01290                                         lhs->type = VALUE;
01291                                 } else if((op->field == ".*" || op->field == "./") && lhs->value.matrix().rows() == rhs->value.matrix().rows() && lhs->value.matrix().cols() == rhs->value.matrix().cols()) {
01292                                         if(lhs->value.isLocal()) {
01293                                                 if(op->field == ".*")
01294                                                         lhs->value.local().array() *= rhs->value.matrix().array();
01295                                                 else // if(op->field == "./")
01296                                                         lhs->value.local().array() /= rhs->value.matrix().array();
01297                                         } else {
01298                                                 if(op->field == ".*")
01299                                                         lhs->value.local() = lhs->value.matrix().array() * rhs->value.matrix().array();
01300                                                 else // if(op->field == "./")
01301                                                         lhs->value.local() = lhs->value.matrix().array() / rhs->value.matrix().array();
01302                                                 lhs->value.mapLocal();
01303                                                 lhs->type = VALUE;
01304                                         }
01305                                 } else if(op->field == "*" && lhs->value.matrix().cols() == rhs->value.matrix().rows()) {
01306                                         if(lhs->value.isLocal()) {
01307                                                 lhs->value.local() *= rhs->value.matrix();
01308                                                 lhs->value.mapLocal();
01309                                         } else {
01310                                                 lhs->value.local() = lhs->value.matrix() * rhs->value.matrix();
01311                                                 lhs->value.mapLocal();
01312                                                 lhs->type = VALUE;
01313                                         }
01314                                 } else {
01315                                         throw std::runtime_error("Invalid operand dimensions for operation '" + lhs->field + op->field + rhs->field + "'.");
01316                                 }
01317                                 chunks.erase(op, rhs + 1);
01318                                 op = lhs + 1;
01319                                 rhs = (op != chunks.end()) ? op + 1 : op;
01320 #ifdef DEBUG
01321 #       ifdef EIGENLAB_DEBUG
01322                                 operationPerformed = true;
01323 #       endif
01324 #endif
01325                         } else {
01326                                 lhs = op;
01327                                 op = rhs;
01328                                 rhs++;
01329                         }
01330                 }
01331 #ifdef DEBUG
01332 #       ifdef EIGENLAB_DEBUG
01333                 if(operationPerformed) { std::cout << "*: "; printChunks(chunks); std::cout << std::endl; }
01334 #       endif
01335 #endif
01336         }
01337 
01338         template <typename Derived>
01339         void Parser<Derived>::evalAddition(ChunkArray & chunks)
01340         {
01341 #ifdef DEBUG
01342 #       ifdef EIGENLAB_DEBUG
01343                 bool operationPerformed = false;
01344 #       endif
01345 #endif
01346                 if(chunks.size() < 3) return;
01347                 typename ChunkArray::iterator lhs = chunks.begin(), op = lhs + 1, rhs = op + 1;
01348                 for(; lhs != chunks.end() && op != chunks.end() && rhs != chunks.end();) {
01349                         if((op->type == OPERATOR) && (op->field == "+" || op->field == "-" || op->field == ".+" || op->field == ".-")) {
01350                                 if(lhs->type == VARIABLE) {
01351                                         if(!isVariable(lhs->field))
01352                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + lhs->field + "'.");
01353                                         lhs->value.setShared(mVariables[lhs->field]);
01354                                 }
01355                                 if(rhs->type == VARIABLE) {
01356                                         if(!isVariable(rhs->field))
01357                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + rhs->field + "'.");
01358                                         rhs->value.setShared(mVariables[rhs->field]);
01359                                 }
01360                                 if(rhs->value.matrix().size() == 1) {
01361                                         if(lhs->value.isLocal()) {
01362                                                 if(op->field == "+" || op->field == ".+")
01363                                                         lhs->value.local().array() += rhs->value.matrix()(0, 0);
01364                                                 else // if(op->field == "-" || op->field == ".-")
01365                                                         lhs->value.local().array() -= rhs->value.matrix()(0, 0);
01366                                         } else {
01367                                                 if(op->field == "+" || op->field == ".+")
01368                                                         lhs->value.local() = lhs->value.matrix().array() + rhs->value.matrix()(0, 0);
01369                                                 else // if(op->field == "-" || op->field == ".-")
01370                                                         lhs->value.local() = lhs->value.matrix().array() - rhs->value.matrix()(0, 0);
01371                                                 lhs->value.mapLocal();
01372                                                 lhs->type = VALUE;
01373                                         }
01374                                 } else if(lhs->value.matrix().size() == 1) {
01375                                         typename Derived::Scalar temp = lhs->value.matrix()(0, 0);
01376                                         if(op->field == "+" || op->field == ".+")
01377                                                 lhs->value.local() = rhs->value.matrix().array() + temp;
01378                                         else // if(op->field == "-" || op->field == ".-")
01379                                                 lhs->value.local() = Derived::Constant(rhs->value.matrix().rows(), rhs->value.matrix().cols(), temp).array() - rhs->value.matrix().array();
01380                                         lhs->value.mapLocal();
01381                                         lhs->type = VALUE;
01382                                 } else if(lhs->value.matrix().rows() == rhs->value.matrix().rows() && lhs->value.matrix().cols() == rhs->value.matrix().cols()) {
01383                                         if(lhs->value.isLocal()) {
01384                                                 if(op->field == "+" || op->field == ".+")
01385                                                         lhs->value.local().array() += rhs->value.matrix().array();
01386                                                 else // if(op->field == "-" || op->field == ".-")
01387                                                         lhs->value.local().array() -= rhs->value.matrix().array();
01388                                         } else {
01389                                                 if(op->field == "+" || op->field == ".+")
01390                                                         lhs->value.local() = lhs->value.matrix().array() + rhs->value.matrix().array();
01391                                                 else // if(op->field == "-" || op->field == ".-")
01392                                                         lhs->value.local() = lhs->value.matrix().array() - rhs->value.matrix().array();
01393                                                 lhs->value.mapLocal();
01394                                                 lhs->type = VALUE;
01395                                         }
01396                                 } else {
01397                                         throw std::runtime_error("Invalid operand dimensions for operation '" + lhs->field + op->field + rhs->field + "'.");
01398                                 }
01399                                 chunks.erase(op, rhs + 1);
01400                                 op = lhs + 1;
01401                                 rhs = (op != chunks.end()) ? op + 1 : op;
01402 #ifdef DEBUG
01403 #       ifdef EIGENLAB_DEBUG
01404                                 operationPerformed = true;
01405 #       endif
01406 #endif
01407                         } else {
01408                                 lhs = op;
01409                                 op = rhs;
01410                                 rhs++;
01411                         }
01412                 }
01413 #ifdef DEBUG
01414 #       ifdef EIGENLAB_DEBUG
01415                 if(operationPerformed) { std::cout << "+: "; printChunks(chunks); std::cout << std::endl; }
01416 #       endif
01417 #endif
01418         }
01419 
01420         template <typename Derived>
01421         void Parser<Derived>::evalAssignment(ChunkArray & chunks)
01422         {
01423 #ifdef DEBUG
01424 #       ifdef EIGENLAB_DEBUG
01425                 bool operationPerformed = false;
01426 #       endif
01427 #endif
01428                 if(chunks.size() < 3) return;
01429                 typename ChunkArray::iterator rhs = chunks.end() - 1, op = rhs - 1, lhs = op - 1;
01430                 for(; op != chunks.begin() && rhs != chunks.begin();) {
01431                         if(op->type == OPERATOR && op->field == "=" && (lhs->type == VALUE || lhs->type == VARIABLE) && (rhs->type == VALUE || rhs->type == VARIABLE)) {
01432                                 if(rhs->type == VARIABLE) {
01433                                         if(!isVariable(rhs->field))
01434                                                 throw std::runtime_error("Attempted operation '" + lhs->field + op->field + rhs->field + "' on uninitialized variable '" + rhs->field + "'.");
01435                                         rhs->value.setShared(mVariables[rhs->field]);
01436                                 }
01437                                 if(lhs->type == VALUE) {
01438                                         lhs->value.local() = rhs->value.matrix();
01439                                         lhs->value.mapLocal();
01440                                 } else { //if(lhs->type == VARIABLE) {
01441                                         if(isVariable(lhs->field)) {
01442                                                 lhs->value.setShared(mVariables[lhs->field]);
01443                                                 if(lhs->row0 == -1) {
01444                                                         if(lhs->value.matrix().rows() == rhs->value.matrix().rows() && lhs->value.matrix().cols() == rhs->value.matrix().cols()) {
01445                                                                 lhs->value.matrix() = rhs->value.matrix();
01446                                                         } else {
01447                                                                 mVariables[lhs->field].local() = rhs->value.matrix();
01448                                                                 mVariables[lhs->field].mapLocal();
01449                                                         }
01450                                                 } else { //if(lhs->row0 != -1) {
01451                                                         lhs->value.matrix().block(lhs->row0, lhs->col0, lhs->rows, lhs->cols) = rhs->value.matrix();
01452                                                 }
01453                                         } else {
01454                                                 mVariables[lhs->field].local() = rhs->value.matrix();
01455                                                 mVariables[lhs->field].mapLocal();
01456                                         }
01457                                 }
01458                                 rhs = chunks.erase(op, rhs + 1);
01459                                 op = (rhs != chunks.begin()) ? rhs - 1 : rhs;
01460                                 if (op != chunks.begin()) lhs = op - 1;
01461 #ifdef DEBUG
01462 #       ifdef EIGENLAB_DEBUG
01463                                 operationPerformed = true;
01464 #       endif
01465 #endif
01466                         } else {
01467                                 rhs = op;
01468                                 op = lhs;
01469                                 lhs--;
01470                         }
01471                 }
01472 #ifdef DEBUG
01473 #       ifdef EIGENLAB_DEBUG
01474                 if(operationPerformed) { std::cout << "=: "; printChunks(chunks); std::cout << std::endl; }
01475 #       endif
01476 #endif
01477         }
01478         
01479 #ifdef DEBUG
01480 #       ifdef EIGENLAB_DEBUG
01481         template <typename Derived>
01482         void Parser<Derived>::printChunks(ChunkArray & chunks, size_t maxRows, size_t maxCols, int precision)
01483         {
01484                 std::cout << "__";
01485                 for(typename ChunkArray::iterator it = chunks.begin(); it != chunks.end(); it++) {
01486                         switch(it->type) {
01487                                 case VALUE:
01488                                         std::cout << textRepresentation(it->value, maxRows, maxCols, precision);
01489                                         if(it->row0 != -1)
01490                                                 std::cout << "(" << it->row0 << ":" << it->row0 + it->rows - 1 << "," << it->col0 << ":" << it->col0 + it->cols - 1 << ")";
01491                                         break;
01492                                 case VARIABLE:
01493                                         std::cout << it->field;// << "=" << textRepresentation(mVariables[it->field], maxRows, maxCols, precision);
01494                                         if(it->row0 != -1)
01495                                                 std::cout << "(" << it->row0 << ":" << it->row0 + it->rows - 1 << "," << it->col0 << ":" << it->col0 + it->cols - 1 << ")";
01496                                         break;
01497                                 case OPERATOR:
01498                                         std::cout << it->field;
01499                                         break;
01500                                 case FUNCTION:
01501                                         std::cout << "f()=" << it->field;
01502                                         break;
01503                         }
01504                         std::cout << "__";
01505                 }
01506         }
01507         
01508         template <typename Derived>
01509         void Parser<Derived>::printVars(size_t maxRows, size_t maxCols, int precision)
01510         {
01511                 for(typename ValueMap::iterator it = mVariables.begin(); it != mVariables.end(); it++)
01512                         std::cout << it->first << " (" << it->second.matrix().rows() << "x" << it->second.matrix().cols() << ") = " << textRepresentation(it->second, maxRows, maxCols, precision) << std::endl;
01513         }
01514         
01515         template <typename Derived>
01516         std::string Parser<Derived>::textRepresentation(Value<Derived> & val, size_t maxRows, size_t maxCols, int precision)
01517         {
01518                 if(val.matrix().size() == 1)
01519                         return numberToString<typename Derived::Scalar>(val.matrix()(0, 0), precision);
01520                 else {
01521                         std::string str = "[";
01522                         for(size_t row = 0; row < val.matrix().rows() && row < maxRows; row++) {
01523                                 str += (row > 0 ? ";[" : "[");
01524                                 for(size_t col = 0; col < val.matrix().cols() && col < maxCols; col++) {
01525                                         if(col > 0) str += ",";
01526                                         str += numberToString<typename Derived::Scalar>(val.matrix()(row, col), precision);
01527                                 }
01528                                 str += (val.matrix().cols() > maxCols ? "...]" : "]");
01529                         }
01530                         str += (val.matrix().rows() > maxRows ? "...]" : "]");
01531                         return str;
01532                 }
01533         }
01534 #       endif // #ifdef EIGENLAB_DEBUG
01535 #endif // #ifdef DEBUG
01536         
01537         template <typename Derived>
01538         std::string Parser<Derived>::trim(const std::string & str)
01539         {
01540                 if(str.size() == 0) return str;
01541                 std::string::const_iterator first = str.begin();
01542                 std::string::const_iterator last = str.end() - 1;
01543                 while(first < last && isspace(*first)) first++;
01544                 while(first < last && isspace(*last)) last--;
01545                 return std::string(first, last + 1);
01546         }
01547         
01548         template <typename Derived>
01549         std::vector<std::string> Parser<Derived>::split(const std::string & str, const char delimeter)
01550         {
01551                 std::vector<std::string> args;
01552                 std::string::const_iterator i0 = str.begin();
01553                 for(std::string::const_iterator it = str.begin(); it != str.end(); it++) {
01554                         if((*it) == delimeter) {
01555                                 args.push_back(trim(std::string(i0, it)));
01556                                 i0 = it + 1;
01557                         }
01558                 }
01559                 args.push_back(std::string(i0, str.end()));
01560                 return args;
01561         }
01562         
01563         template <typename Derived>
01564         template <typename T>
01565         bool Parser<Derived>::isNumber(const std::string & str, T * num)
01566         {
01567                 std::istringstream iss(str);
01568                 if(num)
01569                         iss >> (* num);
01570                 else {
01571                         T number;
01572                         iss >> number;
01573                 }
01574                 return (!iss.fail() && !iss.bad() && iss.eof());
01575         }
01576         
01577         template <typename Derived>
01578         template<typename T>
01579         T Parser<Derived>::stringToNumber(const std::string & str)
01580         {
01581                 std::istringstream iss(str);
01582                 T number;
01583                 iss >> number;
01584                 if(iss.fail() || iss.bad() || !iss.eof())
01585                         throw std::runtime_error("Failed to convert " + str + " to a number.");
01586                 return number;
01587         }
01588         
01589         template <typename Derived>
01590         template<typename T>
01591         std::string Parser<Derived>::numberToString(T num, int precision)
01592         {
01593                 std::ostringstream oss;
01594                 if(precision)
01595                         oss << std::setprecision(precision) << num;
01596                 else
01597                         oss << num;
01598                 return oss.str();
01599         }
01600         
01601 #ifdef DEBUG
01602         template <typename Derived>
01603         void
01604         Parser<Derived>::test_w_lt(size_t & numFails,
01605                                    typename Derived::Scalar & /* s */,
01606                                    Derived & a34,
01607                                    Derived & b34,
01608                                    Derived & /* c43 */,
01609                                    Derived & /* v */, std::true_type)
01610         {
01611                 //
01612                 // tests that only work if Derived::Scalar has operator<
01613                 //
01614                 Value<Derived> resultValue;
01615                 Derived resultMatrix;
01616                 Derived temp;
01617                 std::cout << "Test min(a): ";
01618                 resultValue = eval("min(a)");
01619                 resultMatrix.setConstant(1, 1, a34.minCoeff());
01620                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01621                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01622 
01623                 std::cout << "Test min(a, 0): ";
01624                 resultValue = eval("min(a, 0)");
01625                 resultMatrix = a34.colwise().minCoeff();
01626                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01627                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01628 
01629                 std::cout << "Test min(a, 1): ";
01630                 resultValue = eval("min(a, 1)");
01631                 resultMatrix = a34.rowwise().minCoeff();
01632                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01633                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01634 
01635                 std::cout << "Test max(a): ";
01636                 resultValue = eval("max(a)");
01637                 resultMatrix.setConstant(1, 1, a34.maxCoeff());
01638                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01639                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01640 
01641                 std::cout << "Test max(a, 0): ";
01642                 resultValue = eval("max(a, 0)");
01643                 resultMatrix = a34.colwise().maxCoeff();
01644                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01645                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01646 
01647                 std::cout << "Test max(a, 1): ";
01648                 resultValue = eval("max(a, 1)");
01649                 resultMatrix = a34.rowwise().maxCoeff();
01650                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01651                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01652 
01653                 std::cout << "Test absmax(a): ";
01654                 resultValue = eval("absmax(a)");
01655                 resultMatrix.setConstant(1, 1, std::abs(a34.maxCoeff()) >= std::abs(a34.minCoeff()) ? a34.maxCoeff() : a34.minCoeff());
01656                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01657                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01658 
01659                 std::cout << "Test absmax(a, 0): ";
01660                 resultValue = eval("absmax(a, 0)");
01661                 resultMatrix = a34.colwise().maxCoeff();
01662                 temp = a34.colwise().minCoeff();
01663                 for(Index i = 0; i < resultMatrix.size(); ++i) {
01664                         if(std::abs(resultMatrix(i)) < std::abs(temp(i)))
01665                                 resultMatrix(i) = temp(i);
01666                 }
01667                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01668                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01669 
01670                 std::cout << "Test absmax(a, 1): ";
01671                 resultValue = eval("absmax(a, 1)");
01672                 resultMatrix = a34.rowwise().maxCoeff();
01673                 temp = a34.rowwise().minCoeff();
01674                 for(Index i = 0; i < resultMatrix.size(); ++i) {
01675                         if(std::abs(resultMatrix(i)) < std::abs(temp(i)))
01676                                 resultMatrix(i) = temp(i);
01677                 }
01678                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01679                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01680 
01681                 std::cout << "Test cwiseMin(a, b): ";
01682                 resultValue = eval("cwiseMin(a, b)");
01683                 resultMatrix = a34.cwiseMin(b34);
01684                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01685                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01686 
01687                 std::cout << "Test cwiseMax(a, b): ";
01688                 resultValue = eval("cwiseMax(a, b)");
01689                 resultMatrix = a34.cwiseMax(b34);
01690                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01691                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01692         }
01693 
01694         template <typename Derived>
01695         void
01696         Parser<Derived>::test_w_lt(size_t & /* numFails */,
01697                                    typename Derived::Scalar & /* s */,
01698                                    Derived & /* a34 */,
01699                                    Derived & /* b34 */,
01700                                    Derived & /* c43 */,
01701                                    Derived & /* v */, std::false_type)
01702         {
01703                 // do nothing
01704         }
01705 
01706         template <typename Derived>
01707         size_t Parser<Derived>::test()
01708         {
01709                 std::cout << std::endl;
01710                 std::cout << "BEGIN unit test for EigenLab..." << std::endl;
01711                 std::cout << "Make sure this function completes successfuly and prints the message "
01712                         "'Successfully completed unit test for EigenLab with no failures.'" << std::endl;
01713                 std::cout << std::endl;
01714                 
01715                 size_t numFails = 0;
01716                 Value<Derived> resultValue;
01717                 Derived resultMatrix;
01718                 Derived temp;
01719                 typename Derived::Scalar s = 2;
01720                 
01721                 Derived a34 = Derived::Random(3, 4);
01722                 Derived b34 = Derived::Random(3, 4);
01723                 Derived c43 = Derived::Random(4, 3);
01724                 Derived v = Derived::Random(1, 10);
01725                 //std::cout << "a34=" << std::endl << a34 << std::endl << std::endl;
01726                 //std::cout << "b34=" << std::endl << b34 << std::endl << std::endl;
01727                 //std::cout << "c43=" << std::endl << c43 << std::endl << std::endl;
01728                 //std::cout << "v=" << std::endl << v << std::endl << std::endl;
01729                 
01730                 var("a").setShared(a34);
01731                 var("b").setShared(b34);
01732                 var("c").setShared(c43);
01733                 var("v").setShared(v);
01734                 var("s").setShared(& s);
01735                 
01737                 std::cout << "Testing basic operations..." << std::endl << std::endl;
01739                 
01740                 std::cout << "Test matrix addition a + b: ";
01741                 resultValue = eval("a + b");
01742                 resultMatrix = a34 + b34;
01743                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01744                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01745                 
01746                 std::cout << "Test matrix/scalar addition a + s: ";
01747                 resultValue = eval("a + s");
01748                 resultMatrix = a34.array() + s;
01749                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01750                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01751                 
01752                 std::cout << "Test scalar/matrix addition s + b: ";
01753                 resultValue = eval("s + b");
01754                 resultMatrix = b34.array() + s;
01755                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01756                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01757                 
01758                 std::cout << "Test matrix addition a .+ b: ";
01759                 resultValue = eval("a .+ b");
01760                 resultMatrix = a34 + b34;
01761                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01762                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01763                 
01764                 std::cout << "Test matrix/scalar addition a .+ s: ";
01765                 resultValue = eval("a .+ s");
01766                 resultMatrix = a34.array() + s;
01767                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01768                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01769                 
01770                 std::cout << "Test scalar/matrix addition s .+ b: ";
01771                 resultValue = eval("s .+ b");
01772                 resultMatrix = b34.array() + s;
01773                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01774                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01775                 
01776                 std::cout << "Test matrix subtraction a - b: ";
01777                 resultValue = eval("a - b");
01778                 resultMatrix = a34 - b34;
01779                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01780                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01781                 
01782                 std::cout << "Test matrix/scalar subtraction a - s: ";
01783                 resultValue = eval("a - s");
01784                 resultMatrix = a34.array() - s;
01785                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01786                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01787                 
01788                 std::cout << "Test scalar/matrix subtraction s - b: ";
01789                 resultValue = eval("s - b");
01790                 resultMatrix = (-b34.array()) + s;
01791                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01792                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01793                 
01794                 std::cout << "Test matrix subtraction a .- b: ";
01795                 resultValue = eval("a .- b");
01796                 resultMatrix = a34 - b34;
01797                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01798                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01799                 
01800                 std::cout << "Test matrix/scalar subtraction a .- s: ";
01801                 resultValue = eval("a .- s");
01802                 resultMatrix = a34.array() - s;
01803                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01804                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01805                 
01806                 std::cout << "Test scalar/matrix subtraction s .- b: ";
01807                 resultValue = eval("s .- b");
01808                 resultMatrix = (-b34.array()) + s;
01809                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01810                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01811                 
01812                 std::cout << "Test matrix negation -a: ";
01813                 resultValue = eval("-a");
01814                 resultMatrix = -a34;
01815                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01816                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01817                 
01818                 std::cout << "Test scalar negation -s: ";
01819                 resultValue = eval("-s");
01820                 resultMatrix.setConstant(1, 1, -s);
01821                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01822                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01823                 
01824                 std::cout << "Test matrix coefficient-wise multiplication a .* b: ";
01825                 resultValue = eval("a .* b");
01826                 resultMatrix = a34.array() * b34.array();
01827                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01828                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01829                 
01830                 std::cout << "Test matrix/scalar coefficient-wise multiplication a * s: ";
01831                 resultValue = eval("a * s");
01832                 resultMatrix = a34.array() * s;
01833                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01834                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01835                 
01836                 std::cout << "Test scalar/matrix coefficient-wise multiplication s * b: ";
01837                 resultValue = eval("s * b");
01838                 resultMatrix = b34.array() * s;
01839                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01840                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01841                 
01842                 std::cout << "Test matrix/scalar coefficient-wise multiplication a .* s: ";
01843                 resultValue = eval("a .* s");
01844                 resultMatrix = a34.array() * s;
01845                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01846                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01847                 
01848                 std::cout << "Test scalar/matrix coefficient-wise multiplication s .* b: ";
01849                 resultValue = eval("s .* b");
01850                 resultMatrix = b34.array() * s;
01851                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01852                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01853                 
01854                 std::cout << "Test matrix coefficient-wise division a ./ b: ";
01855                 resultValue = eval("a ./ b");
01856                 resultMatrix = a34.array() / b34.array();
01857                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01858                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01859                 
01860                 std::cout << "Test matrix/scalar coefficient-wise division a / s: ";
01861                 resultValue = eval("a / s");
01862                 resultMatrix = a34.array() / s;
01863                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01864                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01865                 
01866                 std::cout << "Test scalar/matrix coefficient-wise division s / b: ";
01867                 resultValue = eval("s / b");
01868                 resultMatrix = Derived::Constant(b34.rows(), b34.cols(), s).array() / b34.array();
01869                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01870                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01871                 
01872                 std::cout << "Test matrix/scalar coefficient-wise division a ./ s: ";
01873                 resultValue = eval("a ./ s");
01874                 resultMatrix = a34.array() / s;
01875                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01876                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01877                 
01878                 std::cout << "Test scalar/matrix coefficient-wise division s ./ b: ";
01879                 resultValue = eval("s ./ b");
01880                 resultMatrix = Derived::Constant(b34.rows(), b34.cols(), s).array() / b34.array();
01881                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01882                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01883                 
01884                 std::cout << "Test matrix coefficient-wise power a .^ b: ";
01885                 resultValue = eval("abs(a) .^ b");
01886                 resultMatrix = a34;
01887                 for(Index i = 0; i < a34.size(); ++i)
01888                         resultMatrix(i) = pow(std::abs(a34(i)), b34(i));
01889                 //              std::cout << std::endl;
01890                 //              std::cout << "a=" << std::endl << a34 << std::endl << std::endl;
01891                 //              std::cout << "b=" << std::endl << b34 << std::endl << std::endl;
01892                 //              std::cout << "val=" << std::endl << resultValue.matrix() << std::endl << std::endl;
01893                 //              std::cout << "mat=" << std::endl << resultMatrix << std::endl << std::endl;
01894                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01895                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01896                 
01897                 std::cout << "Test matrix/scalar coefficient-wise power a ^ s: ";
01898                 resultValue = eval("abs(a) ^ s");
01899                 resultMatrix = a34;
01900                 for(Index i = 0; i < a34.size(); ++i)
01901                         resultMatrix(i) = pow(std::abs(a34(i)), s);
01902                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01903                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01904                 
01905                 std::cout << "Test scalar/matrix coefficient-wise power s ^ b: ";
01906                 resultValue = eval("s ^ b");
01907                 resultMatrix = b34;
01908                 for(Index i = 0; i < b34.size(); ++i)
01909                         resultMatrix(i) = pow(s, b34(i));
01910                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01911                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01912                 
01913                 std::cout << "Test matrix/scalar coefficient-wise power a .^ s: ";
01914                 resultValue = eval("abs(a) .^ s");
01915                 resultMatrix = a34;
01916                 for(Index i = 0; i < a34.size(); ++i)
01917                         resultMatrix(i) = pow(std::abs(a34(i)), s);
01918                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01919                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01920                 
01921                 std::cout << "Test scalar/matrix coefficient-wise power s .^ b: ";
01922                 resultValue = eval("s .^ b");
01923                 resultMatrix = b34;
01924                 for(Index i = 0; i < b34.size(); ++i)
01925                         resultMatrix(i) = pow(s, b34(i));
01926                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01927                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01928                 
01929                 std::cout << "Test matrix multiplication a * b: ";
01930                 resultValue = eval("a * c");
01931                 resultMatrix = a34 * c43;
01932                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01933                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01934                 
01935                 std::cout << "Test grouped subexpression (a + b) * c: ";
01936                 resultValue = eval("(a + b) * c");
01937                 resultMatrix = (a34 + b34) * c43;
01938                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01939                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01940                 
01941                 std::cout << "Test nested groups ((a + (b * 3 + 1)) * c).^2: ";
01942                 resultValue = eval("((a + (b * 3 + 1)) * c).^2");
01943                 resultMatrix = ((a34.array() + (b34.array() * 3 + 1)).matrix() * c43).array().pow(2);
01944                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01945                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01946                 
01948                 std::cout << std::endl << "Testing coefficient and submatrix block access..." << std::endl << std::endl;
01950                 
01951                 std::cout << "Test matrix coefficient access a(i,j): ";
01952                 resultValue = eval("a(1,2)");
01953                 resultMatrix.setConstant(1, 1, a34(1,2));
01954                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01955                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01956                 
01957                 std::cout << "Test submatrix block access a(i:p,j:q): ";
01958                 resultValue = eval("a(1:2,2:3)");
01959                 resultMatrix = a34.block(1, 2, 2, 2);
01960                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01961                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01962                 
01963                 std::cout << "Test submatrix block access using 'end' and ':' identifiers a(i:end,:): ";
01964                 resultValue = eval("a(1:end,:)");
01965                 resultMatrix = a34.block(1, 0, a34.rows() - 1, a34.cols());
01966                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01967                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01968                 
01969                 std::cout << "Test submatrix block access using subexpressions: ";
01970                 resultValue = eval("a(2-1:2-1,0+1:3-1)");
01971                 resultMatrix = a34.block(1, 1, 1, 2);
01972                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01973                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01974                 
01975                 std::cout << "Test submatrix block access using subexpressions with 'end' keyword: ";
01976                 resultValue = eval("a(2-1:end-1,0+1:end-1)");
01977                 resultMatrix = a34.block(1, 1, a34.rows() - 2, a34.cols() - 2);
01978                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01979                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01980                 
01981                 std::cout << "Test vector coefficient access v(i): ";
01982                 resultValue = eval("v(5)");
01983                 resultMatrix.setConstant(1, 1, v(5));
01984                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01985                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01986                 
01987                 std::cout << "Test subvector segment access v(i:j): ";
01988                 resultValue = eval("v(3:6)");
01989                 resultMatrix = v.block(0, 3, 1, 4);
01990                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01991                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01992                 
01993                 std::cout << "Test subvector segment access using 'end' identifier v(i:end): ";
01994                 resultValue = eval("v(5:end)");
01995                 resultMatrix = v.block(0, 5, 1, v.cols() - 5);
01996                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
01997                 else { std::cout << "FAIL" << std::endl; ++numFails; }
01998                 
01999                 std::cout << "Test subvector segment access using ':' identifier v(:): ";
02000                 resultValue = eval("v(:)");
02001                 resultMatrix = v;
02002                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02003                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02004                 
02005                 std::cout << "Test subvector segment access using subexpressions: ";
02006                 resultValue = eval("v(3-1:5+2)");
02007                 resultMatrix = v.block(0, 2, 1, 6);
02008                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02009                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02010                 
02011                 std::cout << "Test subvector segment access using subexpressions with 'end' keyword: ";
02012                 resultValue = eval("v((end-8)*2:end-3)");
02013                 resultMatrix = v.block(0, 2, 1, 5);
02014                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02015                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02016                 
02018                 std::cout << std::endl << "Testing vector/matrix expressions..." << std::endl << std::endl;
02020                 
02021                 std::cout << "Test numeric range expression [i:j]: ";
02022                 resultValue = eval("[2:5]");
02023                 resultMatrix.resize(1, 4);
02024                 resultMatrix << 2, 3, 4, 5;
02025                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02026                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02027                 
02028                 std::cout << "Test numeric range expression [i:s:j]: ";
02029                 resultValue = eval("[2:2:10]");
02030                 resultMatrix.resize(1, 5);
02031                 resultMatrix << 2, 4, 6, 8, 10;
02032                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02033                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02034                 
02035                 std::cout << "Test numeric range with subexpressions: ";
02036                 resultValue = eval("[6-2:5*2-3]");
02037                 std::cout << "val=" << std::endl << resultValue.matrix() << std::endl << std::endl;
02038                 resultMatrix.resize(1, 4);
02039                 resultMatrix << 4, 5, 6, 7;
02040                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02041                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02042                 
02043                 std::cout << "Test matrix expression [[1, 2]; [3, 4]]: ";
02044                 resultValue = eval("[[1, 2]; [3, 4]]");
02045                 resultMatrix.resize(2, 2);
02046                 resultMatrix << 1, 2, 3, 4;
02047                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02048                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02049                 
02050                 std::cout << "Test matrix expression [  1, 2, 3;        4:6 ]: ";
02051                 resultValue = eval("[1, 2, 3;   4:6]");
02052                 resultMatrix.resize(2, 3);
02053                 resultMatrix << 1, 2, 3, 4, 5, 6;
02054                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02055                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02056                 
02058                 std::cout << std::endl << "Testing coefficient-wise functions..." << std::endl << std::endl;
02060                 
02061                 std::cout << "Test coefficient-wise abs(a): ";
02062                 resultValue = eval("abs(a)");
02063                 resultMatrix.resize(3, 4);
02064                 resultMatrix.real() = a34.array().abs();
02065                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02066                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02067                 
02068                 std::cout << "Test coefficient-wise sqrt(a): ";
02069                 resultValue = eval("sqrt(abs(a))");
02070                 resultMatrix.real() = a34.array().abs().sqrt();
02071                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02072                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02073                 
02074                 std::cout << "Test coefficient-wise exp(a): ";
02075                 resultValue = eval("exp(abs(a) + 0.001)");
02076                 resultMatrix.real() = (a34.array().abs() + 0.001).exp();
02077                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02078                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02079                 
02080                 std::cout << "Test coefficient-wise log(a): ";
02081                 resultValue = eval("log(abs(a) + 0.001)");
02082                 resultMatrix.real() = (a34.array().abs() + 0.001).log();
02083                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02084                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02085                 
02086                 std::cout << "Test coefficient-wise log10(a): ";
02087                 resultValue = eval("log10(abs(a) + 0.001)");
02088                 resultMatrix.real() = (a34.array().abs() + 0.001).log() * (1.0 / log(10));
02089                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02090                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02091                 
02092                 std::cout << "Test coefficient-wise sin(a): ";
02093                 resultValue = eval("sin(a)");
02094                 resultMatrix = a34.array().sin();
02095                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02096                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02097                 
02098                 std::cout << "Test coefficient-wise cos(a): ";
02099                 resultValue = eval("cos(a)");
02100                 resultMatrix = a34.array().cos();
02101                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02102                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02103                 
02104                 std::cout << "Test coefficient-wise tan(a): ";
02105                 resultValue = eval("tan(a)");
02106                 resultMatrix = a34.array().tan();
02107                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02108                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02109                 
02110                 std::cout << "Test coefficient-wise asin(a): ";
02111                 resultValue = eval("asin(a)");
02112                 resultMatrix = a34.array().asin();
02113                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02114                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02115                 
02116                 std::cout << "Test coefficient-wise acos(a): ";
02117                 resultValue = eval("acos(a)");
02118                 resultMatrix = a34.array().acos();
02119                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02120                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02121                 
02123                 std::cout << std::endl << "Testing matrix reduction functions..." << std::endl << std::endl;
02125                 
02126                 std::cout << "Test trace(a): ";
02127                 resultValue = eval("trace(a)");
02128                 resultMatrix.setConstant(1, 1, a34.trace());
02129                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02130                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02131                 
02132                 std::cout << "Test norm(a): ";
02133                 resultValue = eval("norm(a)");
02134                 resultMatrix.setConstant(1, 1, a34.norm());
02135                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02136                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02137                 
02138                 std::cout << "Test size(a, 0): ";
02139                 resultValue = eval("size(a, 0)");
02140                 resultMatrix.setConstant(1, 1, a34.rows());
02141                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02142                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02143                 
02144                 std::cout << "Test size(a, 1): ";
02145                 resultValue = eval("size(a, 1)");
02146                 resultMatrix.setConstant(1, 1, a34.cols());
02147                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02148                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02149                 
02150                 test_w_lt(numFails, s, a34, b34, c43, v, has_operator_lt<typename Derived::Scalar>());
02151                 
02152                 std::cout << "Test mean(a): ";
02153                 resultValue = eval("mean(a)");
02154                 resultMatrix.setConstant(1, 1, a34.mean());
02155                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02156                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02157                 
02158                 std::cout << "Test mean(a, 0): ";
02159                 resultValue = eval("mean(a, 0)");
02160                 resultMatrix = a34.colwise().mean();
02161                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02162                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02163                 
02164                 std::cout << "Test mean(a, 1): ";
02165                 resultValue = eval("mean(a, 1)");
02166                 resultMatrix = a34.rowwise().mean();
02167                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02168                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02169                 
02170                 std::cout << "Test sum(a): ";
02171                 resultValue = eval("sum(a)");
02172                 resultMatrix.setConstant(1, 1, a34.sum());
02173                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02174                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02175                 
02176                 std::cout << "Test sum(a, 0): ";
02177                 resultValue = eval("sum(a, 0)");
02178                 resultMatrix = a34.colwise().sum();
02179                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02180                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02181                 
02182                 std::cout << "Test sum(a, 1): ";
02183                 resultValue = eval("sum(a, 1)");
02184                 resultMatrix = a34.rowwise().sum();
02185                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02186                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02187                 
02188                 std::cout << "Test prod(a): ";
02189                 resultValue = eval("prod(a)");
02190                 resultMatrix.setConstant(1, 1, a34.prod());
02191                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02192                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02193                 
02194                 std::cout << "Test prod(a, 0): ";
02195                 resultValue = eval("prod(a, 0)");
02196                 resultMatrix = a34.colwise().prod();
02197                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02198                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02199                 
02200                 std::cout << "Test prod(a, 1): ";
02201                 resultValue = eval("prod(a, 1)");
02202                 resultMatrix = a34.rowwise().prod();
02203                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02204                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02205                 
02207                 std::cout << std::endl << "Testing matrix functions..." << std::endl << std::endl;
02209                 
02210                 std::cout << "Test transpose(a): ";
02211                 resultValue = eval("transpose(a)");
02212                 resultMatrix = a34.transpose();
02213                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02214                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02215                 
02216                 std::cout << "Test conjugate(a): ";
02217                 resultValue = eval("conjugate(a)");
02218                 resultMatrix = a34.conjugate();
02219                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02220                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02221                 
02222                 std::cout << "Test adjoint(a): ";
02223                 resultValue = eval("adjoint(a)");
02224                 resultMatrix = a34.adjoint();
02225                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02226         else { std::cout << "FAIL" << std::endl; ++numFails; }
02227         
02229         std::cout << std::endl << "Testing matrix initializers..." << std::endl << std::endl;
02231         
02232         std::cout << "Test zeros(5): ";
02233         resultValue = eval("zeros(5)");
02234         resultMatrix = Derived::Zero(5, 5);
02235         if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02236         else { std::cout << "FAIL" << std::endl; ++numFails; }
02237         
02238         std::cout << "Test ones(5): ";
02239         resultValue = eval("ones(5)");
02240         resultMatrix = Derived::Ones(5, 5);
02241         if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02242         else { std::cout << "FAIL" << std::endl; ++numFails; }
02243         
02244         std::cout << "Test eye(5): ";
02245         resultValue = eval("eye(5)");
02246         resultMatrix = Derived::Identity(5, 5);
02247         if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02248         else { std::cout << "FAIL" << std::endl; ++numFails; }
02249         
02250         try {
02251             std::cout << "Test zeros(5.2): ";
02252             resultValue = eval("zeros(5.2)"); // <-- Should NOT succeed!!!
02253             std::cout << "FAIL" << std::endl; ++numFails;
02254         } catch(std::runtime_error &err) {
02255             std::cout << err.what() << std::endl;
02256             std::cout << "Exception caught, so we're OK" << std::endl;
02257         }
02258         
02259         try {
02260             std::cout << "Test eye(-3): ";
02261             resultValue = eval("eye(-3)"); // <-- Should NOT succeed!!!
02262             std::cout << "FAIL" << std::endl; ++numFails;
02263         } catch(std::runtime_error &err) {
02264             std::cout << err.what() << std::endl;
02265             std::cout << "Exception caught, so we're OK" << std::endl;
02266         }
02267         
02268         std::cout << "Test zeros(4,7): ";
02269         resultValue = eval("zeros(4,7)");
02270         resultMatrix = Derived::Zero(4, 7);
02271         if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02272         else { std::cout << "FAIL" << std::endl; ++numFails; }
02273         
02274         std::cout << "Test ones(4,7): ";
02275         resultValue = eval("ones(4,7)");
02276         resultMatrix = Derived::Ones(4, 7);
02277         if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02278         else { std::cout << "FAIL" << std::endl; ++numFails; }
02279         
02280         std::cout << "Test eye(4,7): ";
02281         resultValue = eval("eye(4,7)");
02282         resultMatrix = Derived::Identity(4, 7);
02283         if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02284         else { std::cout << "FAIL" << std::endl; ++numFails; }
02285                 
02287                 std::cout << std::endl << "Testing variable assignment..." << std::endl << std::endl;
02289                 
02290                 std::cout << "Test assigning to a variable with the same dimensions a = b: ";
02291                 eval("a = b");
02292                 if(a34.isApprox(b34)) std::cout << "OK" << std::endl;
02293                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02294                 
02295                 std::cout << "Test assigning to a variable with different dimensions a = c: ";
02296                 eval("a = c");
02297                 if(var("a").matrix().isApprox(c43) && a34.isApprox(b34)) std::cout << "OK" << std::endl;
02298                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02299                 var("a").setShared(a34);
02300                 
02301                 std::cout << "Test creating a new variable x = [1,2;3,4]: ";
02302                 resultValue = eval("x = [1,2;3,4]");
02303                 if(var("x").matrix().isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02304                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02305                 
02306                 std::cout << "Test assigning to a variable coefficient a(i,j) = s: ";
02307                 eval("a(1, 2) = s");
02308                 if(a34(1, 2) == s) std::cout << "OK" << std::endl;
02309                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02310                 
02311                 std::cout << "Test assigning to a variable submatrix block a(0:1,1:2) = x: ";
02312                 resultValue = eval("a(0:1,1:2) = x");
02313                 if(a34.block(0,1,2,2).isApprox(var("x").matrix())) std::cout << "OK" << std::endl;
02314                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02315                 
02316         try {
02317             std::cout << "Test bad function call: ";
02318             resultValue = eval("foobar(-3)"); // <-- Should NOT succeed!!!
02319             std::cout << "FAIL" << std::endl; ++numFails;
02320         } catch(std::runtime_error &err) {
02321             std::cout << err.what() << std::endl;
02322             std::cout << "Exception caught, so we're OK" << std::endl;
02323         }
02325                 std::cout << std::endl << "Testing fp parsing..." << std::endl << std::endl;
02327 
02328                 std::cout << "Test assigning 1.2e-3: ";
02329                 resultValue = eval("s = 1.2e-3");
02330                 resultMatrix.setConstant(1, 1, typename Derived::Scalar(1.2e-3));
02331                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02332                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02333 
02334                 std::cout << "Test assigning 1.e3: ";
02335                 resultValue = eval("s = 1.e3");
02336                 resultMatrix.setConstant(1, 1, typename Derived::Scalar(1000));
02337                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02338                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02339 
02340                 std::cout << "Test assigning 12.34e05: ";
02341                 resultValue = eval("s = 12.34e05");
02342                 resultMatrix.setConstant(1, 1, typename Derived::Scalar(123.4e4));
02343                 if(resultMatrix.isApprox(resultValue.matrix())) std::cout << "OK" << std::endl;
02344                 else { std::cout << "FAIL" << std::endl; ++numFails; }
02345 
02346                 std::cout << std::endl;
02347                 if(numFails == 0)
02348                         std::cout << "Successfully completed unit test for EigenLab with no failures." << std::endl;
02349                 else
02350                         std::cout << "Completed unit test for EigenLab with " << numFails << " failures (see above)." << std::endl;
02351                 std::cout << std::endl;
02352                 return numFails;
02353         }
02354 #endif // #ifdef DEBUG
02355 
02356 } // namespace EigenLab
02357 
02358 #endif // #ifndef EigenLab_H


grid_map_filters
Author(s): Péter Fankhauser , Martin Wermelinger
autogenerated on Mon Oct 9 2017 03:09:30