Program Listing for File formatters.hpp

Return to documentation for file (/tmp/ws/src/ecl_core/ecl_linear_algebra/include/ecl/linear_algebra/eigen/formatters.hpp)

/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef ECL_LINEAR_ALGEBRA_FORMATTERS_HPP_
#define ECL_LINEAR_ALGEBRA_FORMATTERS_HPP_

/*****************************************************************************
** Includes
*****************************************************************************/

#include <ecl/exceptions/standard_exception.hpp>
#include <ecl/formatters.hpp>
#include <ecl/mpl/enable_if.hpp>
#include <ecl/type_traits/fundamental_types.hpp>

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace Eigen {

/*****************************************************************************
** Interface [MatrixFormatter]
*****************************************************************************/

template <typename Derived, typename Scalar, typename Enable = void>
class MatrixFormatter {
private:
    MatrixFormatter() {}
};

/*****************************************************************************
** Interface [FloatMatrixFormatter]
*****************************************************************************/

template<typename Derived>
class FloatMatrixFormatter {
public:
    /******************************************
    ** C&D's
    *******************************************/
    FloatMatrixFormatter(const int &w = -1, const unsigned int &p = 2) :
        tmp_formatting(false),
        ready_to_format(false),
        _matrix(NULL)
    {
        format.width(w);
        format.precision(p);
    }
    virtual ~FloatMatrixFormatter() {}

    /******************************************
    ** Configuration
    *******************************************/
    FloatMatrixFormatter<Derived>& precision( const unsigned int &p ) {
        format.precision(p);
        return *this;
    }

    FloatMatrixFormatter<Derived>& width( const int &w ) {
        format.width(w);
        return *this;
    }

    unsigned int precision() { return format.precision(); }

    int width() { return format.width(); }

    /******************************************
    ** Format a value
    *******************************************/
    FloatMatrixFormatter< Derived >& operator() (const Derived & matrix ) {
        _matrix = &matrix;
        ready_to_format = true;
        return (*this);
    }
    FloatMatrixFormatter< Derived >& operator() (const Derived & matrix, const int &w, const unsigned int &p) {
        _matrix = &matrix;
        tmp_precision = p;
        tmp_width = w;
        tmp_formatting = true;
        ready_to_format = true;
        return (*this);
    }

    template <typename OutputStream, typename Derived_ >
    friend OutputStream& operator << ( OutputStream& ostream, FloatMatrixFormatter<Derived_> & formatter );

    private:
        ecl::Format<typename Derived::Scalar> format;
        int tmp_width;
        unsigned int tmp_precision;
        bool tmp_formatting;
        bool ready_to_format;
        const Derived *_matrix;
};

template <typename OutputStream, typename Derived_ >
OutputStream& operator << (OutputStream& ostream, FloatMatrixFormatter< Derived_ > & formatter )
{
    ecl_assert_throw( formatter._matrix, ecl::StandardException(LOC,ecl::UsageError,"The formatter cannot print any data - "
            "_matrix was not initialised "
            "please pass the your matrix through () operator") );
    ecl_assert_throw(formatter.ready_to_format, ecl::StandardException(LOC,ecl::UsageError,"The formatter cannot print any data - "
            "either there is no data available, or you have tried to use the "
            "formatter more than once in a single streaming operation. "
            "C++ produces unspecified results when functors are used multiply "
            "in the same stream sequence, so this is not permitted here.") );


    if ( formatter.ready_to_format ) {
        unsigned int prm_precision = formatter.format.precision();;
        int prm_width = formatter.format.width();
        if ( formatter.tmp_formatting ) {
            formatter.format.precision(formatter.tmp_precision);
            formatter.format.width(formatter.tmp_width);
        }

        /*********************
        ** Stream Matrix
        **********************/
        // write matrix data
        // @note norma matrix allows matrix(i,j) however sparse matrix does not.
        // So i put coeff(i,j) function which can be used for accessing each element for both of sparse and dense.
        int rows = formatter._matrix->rows();
        int cols = formatter._matrix->cols();
        for( int i=0; i<rows; i++ )
        {
            for( int j=0; j<cols; j++ )
            {
                ostream <<  formatter.format(formatter._matrix->coeff( i, j )) << "  ";
            }
            if ( rows != 1 ) {  // special condition for row vectors so we can do inline the formatting.
              ostream << "\n";
            }
        }

        if ( formatter.tmp_formatting ) {
            formatter.format.precision(prm_precision);
            formatter.format.width(prm_width);
            formatter.tmp_formatting = false;
        }
        formatter.ready_to_format = false;
    }
    return ostream;
}

/*****************************************************************************
** Interface [MatrixFormatter][Float Types]
*****************************************************************************/

template <typename Derived, typename Scalar>
class MatrixFormatter<Derived, Scalar, typename ecl::enable_if< ecl::is_float<Scalar> >::type> : public FloatMatrixFormatter<Derived> {
public:
    MatrixFormatter(const int &w = -1, const unsigned int &p = 2) : FloatMatrixFormatter<Derived>(w, p) {};
};

} // namespace Eigen

#endif /* ECL_LINEAR_ALGEBRA_FORMATTERS_HPP_ */