From 4e618d67a5560805e9c559781ca4efc25e98bbcc Mon Sep 17 00:00:00 2001
From: Pietro Incardona <i-bird@localhost.localdomain>
Date: Sun, 26 Jun 2016 21:37:55 +0200
Subject: [PATCH] Support for vector dist operators

---
 .../Vector/vector_dist_operators.hpp          | 283 ++++++------------
 .../vector_dist_operators_unit_tests.hpp      | 253 +++++++++-------
 2 files changed, 238 insertions(+), 298 deletions(-)

diff --git a/src/Operators/Vector/vector_dist_operators.hpp b/src/Operators/Vector/vector_dist_operators.hpp
index 64918f01..2d7f90f5 100644
--- a/src/Operators/Vector/vector_dist_operators.hpp
+++ b/src/Operators/Vector/vector_dist_operators.hpp
@@ -8,6 +8,7 @@
 #ifndef OPENFPM_NUMERICS_SRC_OPERATORS_VECTOR_VECTOR_DIST_OPERATORS_HPP_
 #define OPENFPM_NUMERICS_SRC_OPERATORS_VECTOR_VECTOR_DIST_OPERATORS_HPP_
 
+#include "Vector/vector_dist.hpp"
 
 #define VECT_SUM 1
 #define VECT_SUB 2
@@ -15,137 +16,19 @@
 #define VECT_DIV 4
 #define VECT_NORM 5
 #define VECT_NORM2 6
-#define VECT_APPLYKER 7
+#define VECT_APPLYKER_IN 7
+#define VECT_APPLYKER_OUT 8
+#define VECT_APPLYKER_REDUCE 9
+#define VECT_APPLYKER_IN_GEN 10
+#define VECT_APPLYKER_OUT_GEN 11
+#define VECT_APPLYKER_REDUCE_GEN 12
+#define VECT_APPLYKER_MULTI_IN 13
+#define VECT_APPLYKER_MULTI_OUT 14
+#define VECT_APPLYKER_MULTI_REDUCE 15
+#define VECT_APPLYKER_MULTI_IN_GEN 16
+#define VECT_APPLYKER_MULTI_OUT_GEN 17
+#define VECT_APPLYKER_MULTI_REDUCE_GEN 18
 
-/*! \brief is_expression check if a type is simple a type or is just an encapsulation of an expression
- *
- * return true if T::is_expression is a valid expression
- *
- */
-
-template<typename ObjType, typename Sfinae = void>
-struct is_expression: std::false_type {};
-
-template<typename ObjType>
-struct is_expression<ObjType, typename Void<typename ObjType::is_expression>::type> : std::true_type
-{};
-
-template<typename exp, bool is_exp = is_expression<exp>::value>
-struct apply_kernel_rtype
-{
-	typedef typename exp::orig_type rtype;
-};
-
-template<typename exp>
-struct apply_kernel_rtype<exp,false>
-{
-	typedef exp rtype;
-};
-
-
-/*! \brief Apply the kernel to particle differently that is a number or is an expression
- *
- *
- */
-template<typename T, typename vector, typename exp,typename NN_type, typename Kernel, typename rtype, bool is_exp=is_expression<T>::value>
-struct apply_kernel_is_number_or_expression
-{
-	inline static rtype apply(const vector & vd, NN_type & cl, const exp & v_exp, const vect_dist_key_dx & key, Kernel & lker)
-	{
-	    // accumulator
-	    rtype pse = static_cast<typename rtype::coord_type>(0.0);
-
-	    // position of particle p
-	    Point<vector::dims,typename vector::stype> p = vd.getPos(key);
-
-	    // property of the particle x
-	    rtype prp_p = v_exp.value(key);
-
-	    // Get the neighborhood of the particle
-	    auto NN = cl.template getNNIterator<NO_CHECK>(cl.getCell(p));
-	    while(NN.isNext())
-	    {
-	    	auto nnp = NN.get();
-
-	    	// Calculate contribution given by the kernel value at position p,
-	    	// given by the Near particle, exclude itself
-	    	if (nnp != key.getKey())
-	    	{
-	    	    // property of the particle x
-	    		rtype prp_q = v_exp.value(nnp);
-
-	    	    // position of the particle q
-	    		Point<vector::dims,typename vector::stype> q = vd.getPos(nnp);
-
-	    	    for (size_t i = 0 ; i < T::nvals ; i++)
-	    	    {
-	    	    	float val = lker.value(p,q,prp_p.value(i),prp_q.value(i));
-
-	    	    	// W(x-y)
-	    	    	pse.value(i) += val;
-	    	    }
-	    	}
-
-	    	// Next particle
-	    	++NN;
-	    }
-
-	    return pse;
-	}
-};
-
-template<typename T, typename vector, typename exp,typename NN_type, typename Kernel, typename rtype>
-struct apply_kernel_is_number_or_expression<T,vector,exp,NN_type,Kernel,rtype,false>
-{
-
-	/*! \brief Apply the kernel
-	 *
-	 * \param cl Neighborhood of particles
-	 * \param v_exp vector expression
-	 * \param key particle id
-	 * \param lker kernel function
-	 *
-	 */
-	inline static rtype apply(const vector & vd, NN_type & cl, const exp & v_exp, const vect_dist_key_dx & key, const Kernel & lker)
-	{
-	    // accumulator
-	    rtype pse = 0;
-
-	    // Get f(x) at the position of the particle
-	    rtype & prp_p = v_exp.value(key);
-
-	    // position of particle p
-	    auto & p = vd.getPos(key);
-
-	    // Get the neighborhood of the particle
-	    auto NN = cl.template getNNIterator<NO_CHECK>(cl.getCell(p));
-	    while(NN.isNext())
-	    {
-	    	auto nnp = NN.get();
-
-	    	// Calculate contribution given by the kernel value at position p,
-	    	// given by the Near particle, exclude itself
-	    	if (nnp != key.getKey())
-	    	{
-	    	    // Get f(x) at the position of the particle
-	    	    rtype & prp_q = vd.getPos(nnp);
-
-	    	    // position of particle q
-	    	    auto & q = v_exp.value_pos(key);
-
-	    		// W(x-y)
-	    		auto ker = lker.value(p,q,prp_p,prp_q);
-
-	    		pse += ker;
-	    	}
-
-	    	// Next particle
-	    	++NN;
-	    }
-
-	    return pse;
-	}
-};
 
 /*! \brief has_init check if a type has defined a
  * method called init
@@ -217,6 +100,17 @@ public:
 	:o1(o1),o2(o2)
 	{}
 
+	/*! \brief This function must be called before value
+	 *
+	 * it initialize the expression if needed
+	 *
+	 */
+	inline void init() const
+	{
+		o1.init();
+		o2.init();
+	}
+
 	/*! \brief Evaluate the expression
 	 *
 	 * \param key where to evaluate the expression
@@ -247,6 +141,17 @@ public:
 	:o1(o1),o2(o2)
 	{}
 
+	/*! \brief This function must be called before value
+	 *
+	 * it initialize the expression if needed
+	 *
+	 */
+	inline void init() const
+	{
+		o1.init();
+		o2.init();
+	}
+
 	/*! \brief Evaluate the expression
 	 *
 	 * \param key where to evaluate the expression
@@ -276,6 +181,17 @@ public:
 	:o1(o1),o2(o2)
 	{}
 
+	/*! \brief This function must be called before value
+	 *
+	 * it initialize the expression if needed
+	 *
+	 */
+	inline void init() const
+	{
+		o1.init();
+		o2.init();
+	}
+
 	/*! \brief Evaluate the expression
 	 *
 	 * \param key where to evaluate the expression
@@ -305,6 +221,17 @@ public:
 	:o1(o1),o2(o2)
 	{}
 
+	/*! \brief This function must be called before value
+	 *
+	 * it initialize the expression if needed
+	 *
+	 */
+	inline void init() const
+	{
+		o1.init();
+		o2.init();
+	}
+
 	/*! \brief Evaluate the expression
 	 *
 	 * \param key where to evaluate the expression
@@ -333,54 +260,28 @@ public:
 	:o1(o1)
 	{}
 
-	/*! \brief Evaluate the expression
+	/*! \brief This function must be called before value
 	 *
-	 * \param key where to evaluate the expression
+	 * it initialize the expression if needed
 	 *
 	 */
-	template<typename r_type=typename std::remove_reference<decltype(norm(o1.value(vect_dist_key_dx(0))))>::type > inline r_type value(const vect_dist_key_dx & key) const
+	inline void init() const
 	{
-		return norm(o1.value(key));
+		o1.init();
 	}
-};
-
-/*! \brief Apply kernel operation
- *
- * \tparam exp1 expression1
- * \tparam NN list
- *
- */
-template <typename exp1,typename vector_type>
-class vector_dist_expression_op<exp1,vector_type,VECT_APPLYKER>
-{
-	typedef typename boost::mpl::at<vector_type,boost::mpl::int_<0>>::type NN;
-	typedef typename boost::mpl::at<vector_type,boost::mpl::int_<1>>::type Kernel;
-	typedef typename boost::mpl::at<vector_type,boost::mpl::int_<2>>::type vector_orig;
-
-	const exp1 o1;
-	NN & cl;
-	Kernel & ker;
-	const vector_orig & vd;
-
-public:
-
-	vector_dist_expression_op(const exp1 & o1, NN & cl, Kernel & ker, const vector_orig & vd)
-	:o1(o1),cl(cl),ker(ker),vd(vd)
-	{}
 
 	/*! \brief Evaluate the expression
 	 *
 	 * \param key where to evaluate the expression
 	 *
 	 */
-	template<typename r_type=typename apply_kernel_rtype<decltype(o1.value(vect_dist_key_dx(0)))>::rtype > inline r_type value(const vect_dist_key_dx & key) const
+	template<typename r_type=typename std::remove_reference<decltype(norm(o1.value(vect_dist_key_dx(0))))>::type > inline r_type value(const vect_dist_key_dx & key) const
 	{
-		typedef typename apply_kernel_rtype<decltype(o1.value(vect_dist_key_dx(0)))>::rtype rtype;
-
-		return apply_kernel_is_number_or_expression<decltype(o1.value(key)),vector_orig,exp1,NN,Kernel,rtype>::apply(vd,cl,o1,key,ker);
+		return norm(o1.value(key));
 	}
 };
 
+
 /*! \brief Main class that encapsulate a vector properties
  *
  * \tparam prp property involved
@@ -398,6 +299,14 @@ public:
 	:v(v)
 	{}
 
+	/*! \brief This function must be called before value
+	 *
+	 * it initialize the expression if needed
+	 *
+	 */
+	inline void init() const
+	{}
+
 	/*! \brief Evaluate the expression
 	 *
 	 * \param key where to evaluate the expression
@@ -416,14 +325,14 @@ public:
 	 */
 	template<typename exp1, typename exp2, unsigned int op> vector & operator=(const vector_dist_expression_op<exp1,exp2,op> & v_exp)
 	{
+		v_exp.init();
+
 		auto it = v.getDomainIterator();
 
 		while (it.isNext())
 		{
 			auto key = it.get();
 
-			auto exp = v_exp.value(key);
-			call_init_if_needed<decltype(exp)>::call(exp);
 			v.template getProp<prp>(key) = v_exp.value(key);
 
 			++it;
@@ -454,6 +363,19 @@ public:
 	}
 };
 
+/*! \Create an expression from a vector
+ *
+ * \tpatam prp property
+ * \param v
+ *
+ */
+template <unsigned int prp,typename vector> inline vector_dist_expression<prp,vector > getV(vector & v)
+{
+	vector_dist_expression<prp,vector > exp_v(v);
+
+	return exp_v;
+}
+
 /*! \brief Main class that encapsulate a double constant
  *
  * \param prp no meaning
@@ -470,6 +392,14 @@ public:
 	:d(d)
 	{}
 
+	/*! \brief This function must be called before value
+	 *
+	 * it initialize the expression if needed
+	 *
+	 */
+	inline void init() const
+	{}
+
 	/*! \brief Evaluate the expression
 	 *
 	 * It just return the velue set in the constructor
@@ -997,27 +927,6 @@ norm(const vector_dist_expression<prp1,v1> & va)
 	return exp_sum;
 }
 
-
-///////////////////////////////////////////// Apply kernel operator ////
-////////////////////////////////////////////////////////////////////////
-
-/* \brief Divide two distributed vector expression
- *
- * \param va vector expression one
- * \param vb vector expression two
- *
- * \return an object that encapsulate the expression
- *
- */
-template<typename exp1, typename exp2, unsigned int op1, typename NN, typename Kernel, typename vector_type>
-inline vector_dist_expression_op<vector_dist_expression_op<exp1,exp2,op1>,boost::mpl::vector<NN,Kernel,vector_type>,VECT_APPLYKER>
-applyKernel(const vector_dist_expression_op<exp1,exp2,op1> & va, vector_type & vd, NN & cl, Kernel & ker)
-{
-	vector_dist_expression_op<vector_dist_expression_op<exp1,exp2,op1>,boost::mpl::vector<NN,Kernel,vector_type>,VECT_APPLYKER> exp_sum(va,cl,ker,vd);
-
-	return exp_sum;
-}
-
-
+#include "vector_dist_operators_apply_kernel.hpp"
 
 #endif /* OPENFPM_NUMERICS_SRC_OPERATORS_VECTOR_VECTOR_DIST_OPERATORS_HPP_ */
diff --git a/src/Operators/Vector/vector_dist_operators_unit_tests.hpp b/src/Operators/Vector/vector_dist_operators_unit_tests.hpp
index ef8f9b24..8da79a29 100644
--- a/src/Operators/Vector/vector_dist_operators_unit_tests.hpp
+++ b/src/Operators/Vector/vector_dist_operators_unit_tests.hpp
@@ -8,13 +8,17 @@
 #ifndef OPENFPM_NUMERICS_SRC_OPERATORS_VECTOR_VECTOR_DIST_OPERATORS_UNIT_TESTS_HPP_
 #define OPENFPM_NUMERICS_SRC_OPERATORS_VECTOR_VECTOR_DIST_OPERATORS_UNIT_TESTS_HPP_
 
+#include "Operators/Vector/vector_dist_operators.hpp"
+
 constexpr int A = 0;
 constexpr int B = 1;
 constexpr int C = 2;
 
-constexpr int PA = 3;
-constexpr int PB = 4;
-constexpr int PC = 5;
+constexpr int VA = 3;
+constexpr int VB = 4;
+constexpr int VC = 5;
+
+constexpr int TA = 6;
 
 //////////////////// Here we define all the function to checl the operators
 
@@ -132,9 +136,15 @@ template <typename rtype, typename vector, unsigned int A, unsigned int B, unsig
 	{
 		auto key = it.get();
 
-		rtype base1 = vd1.template getProp<B>(key) + vd1.template getProp<C>(key) + vd1.template getProp<B>(key) + vd1.template getProp<C>(key);
+		rtype base1 = (vd1.template getProp<B>(key) + vd1.template getProp<C>(key)) + (vd1.template getProp<B>(key) + vd1.template getProp<C>(key));
 		rtype base2 = vd1.template getProp<A>(key);
 
+		if (base1 != base2)
+		{
+			int debug = 0;
+			debug++;
+		}
+
 		ret &=  base1 == base2;
 
 		++it;
@@ -513,7 +523,7 @@ template <typename vector> bool check_values_scal_norm_dist(vector & vd)
 	{
 		auto key = it.get();
 
-		float base1 = vd.template getProp<PB>(key) * vd.template getProp<PC>(key) + norm(vd.template getProp<PC>(key) + vd.template getProp<PB>(key)) + distance(vd.template getProp<PC>(key),vd.template getProp<PB>(key));
+		float base1 = vd.template getProp<VB>(key) * vd.template getProp<VC>(key) + norm(vd.template getProp<VC>(key) + vd.template getProp<VB>(key)) + distance(vd.template getProp<VC>(key),vd.template getProp<VB>(key));
 		float base2 = vd.template getProp<A>(key);
 
 		ret &=  base1 == base2;
@@ -534,21 +544,27 @@ template <typename vector> void fill_values(const vector & v)
 	{
 		auto p = it.get();
 
-		v.template getProp<A>(p) = p.getKey()+1;
-		v.template getProp<B>(p) = 2.0*p.getKey()+1;
-		v.template getProp<C>(p) = 3.0*p.getKey()+1;
+		v.getPos(p)[0] = (float)rand() / RAND_MAX;
+		v.getPos(p)[1] = (float)rand() / RAND_MAX;
+		v.getPos(p)[2] = (float)rand() / RAND_MAX;
+
+		v.template getProp<A>(p) = fabs(sin(p.getKey()+1));
+		v.template getProp<B>(p) = fabs(sin(2.0*p.getKey()+3));
+		v.template getProp<C>(p) = fabs(sin(3.0*p.getKey()+18));
 
 		for (size_t k = 0 ; k < 3 ; k++)
 		{
-			v.template getProp<PA>(p)[k] = p.getKey()+1+k;
-			v.template getProp<PB>(p)[k] = 2.0*p.getKey()+1+k;
-			v.template getProp<PC>(p)[k] = 3.0*p.getKey()+1+k;
+			v.template getProp<VA>(p)[k] = fabs(sin(p.getKey()+1+k));
+			v.template getProp<VB>(p)[k] = fabs(sin(2.0*p.getKey()+1+3));
+			v.template getProp<VC>(p)[k] = fabs(sin(3.0*p.getKey()+1+k));
 		}
 
 		++it;
 	}
 }
 
+typedef vector_dist<3,float,aggregate<float,float,float,VectorS<3,float>,VectorS<3,float>,VectorS<3,float>>> vector_type;
+
 //! Exponential kernel
 struct exp_kernel
 {
@@ -558,11 +574,25 @@ struct exp_kernel
 	:var(var)
 	{}
 
-	inline float value(Point<3,float> & p, Point<3,float> q,float pA,float pB)
+	inline float value(const Point<3,float> & p, const Point<3,float> & q,float pA,float pB)
+	{
+		float dist = norm(p-q);
+
+		return (pA + pB) * exp(dist * dist / var);
+	}
+
+	inline Point<3,float> value(const Point<3,float> & p, const Point<3,float> & q,const Point<3,float> & pA, const Point<3,float> & pB)
 	{
 		float dist = norm(p-q);
 
-		return (pA - pB) * exp(dist * dist / var);
+		return (pA + pB) * exp(dist * dist / var);
+	}
+
+	inline Point<3,float> value(vector_type & vd1, vector_type & vd2, size_t p, size_t q, float pA, float pB)
+	{
+		float dist = norm(p-q);
+
+		return (pA + pB) * exp(dist * dist / var);
 	}
 };
 
@@ -589,9 +619,17 @@ BOOST_AUTO_TEST_CASE( vector_dist_operators_test )
 
 	vector_dist<3,float,aggregate<float,float,float,VectorS<3,float>,VectorS<3,float>,VectorS<3,float>>> vd(100,box,bc,ghost);
 
-	vd.getV<A>() = 1.0;
-	vd.getV<B>() = 2.0f;
-	vd.getV<C>() = 3.0;
+	auto vA = getV<A>(vd);
+	auto vB = getV<B>(vd);
+	auto vC = getV<C>(vd);
+
+	auto vVA = getV<VA>(vd);
+	auto vVB = getV<VB>(vd);
+	auto vVC = getV<VC>(vd);
+
+	vA = 1.0;
+	vB = 2.0f;
+	vC = 3.0;
 
 	check_values<A>(vd,1.0);
 	check_values<B>(vd,2.0);
@@ -599,153 +637,146 @@ BOOST_AUTO_TEST_CASE( vector_dist_operators_test )
 
 	fill_values(vd);
 
-	vd.getV<A>() = vd.getV<B>() + 2.0 + vd.getV<B>() - 2.0*vd.getV<C>() / 5.0;
+	vA = vB + 2.0 + vB - 2.0*vC / 5.0;
 	check_values_complex_expr(vd);
 
 	// Various combination of 2 operator
 
-	vd.getV<A>() = vd.getV<B>() + 2.0;
+	vA = vB + 2.0;
 	check_values_sum<float,vtype,A,B,C>(vd,2.0);
-	vd.getV<A>() = 2.0 + vd.getV<B>();
+	vA = 2.0 + vB;
 	check_values_sum<float,vtype,A,B,C>(vd,2.0);
-	vd.getV<A>() = vd.getV<C>() + vd.getV<B>();
+	vA = vC + vB;
 	check_values_sum<float,vtype,A,B,C>(vd,vd);
 
-	vd.getV<A>() = vd.getV<B>() - 2.0;
+	vA = vB - 2.0;
 	check_values_sub<float,vtype,A,B,C>(vd,2.0);
-	vd.getV<A>() = 2.0 - vd.getV<B>();
+	vA = 2.0 - vB;
 	check_values_sub<float,vtype,A,B,C>(2.0,vd);
-	vd.getV<A>() = vd.getV<C>() - vd.getV<B>();
+	vA = vC - vB;
 	check_values_sub<float,vtype,A,B,C>(vd,vd);
 
-	vd.getV<A>() = vd.getV<B>() * 2.0;
+	vA = vB * 2.0;
 	check_values_mul<float,vtype,A,B,C>(vd,2.0);
-	vd.getV<A>() = 2.0 * vd.getV<B>();
+	vA = 2.0 * vB;
 	check_values_mul<float,vtype,A,B,C>(vd,2.0);
-	vd.getV<A>() = vd.getV<C>() * vd.getV<B>();
+	vA = vC * vB;
 	check_values_mul<float,vtype,A,B,C>(vd,vd);
 
-	vd.getV<A>() = vd.getV<B>() / 2.0;
+	vA = vB / 2.0;
 	check_values_div<float,vtype,A,B,C>(vd,2.0);
-	vd.getV<A>() = 2.0 / vd.getV<B>();
+	vA = 2.0 / vB;
 	check_values_div<float,vtype,A,B,C>(2.0,vd);
-	vd.getV<A>() = vd.getV<C>() / vd.getV<B>();
+	vA = vC / vB;
 	check_values_div<float,vtype,A,B,C>(vd,vd);
 
 	// Variuos combination 3 operator
 
-	vd.getV<A>() = vd.getV<B>() + (vd.getV<C>() + vd.getV<B>());
+	vA = vB + (vC + vB);
 	check_values_sum_3<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) + vd.getV<B>();
+	vA = (vC + vB) + vB;
 	check_values_sum_3<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) + (vd.getV<C>() + vd.getV<B>());
+	vA = (vC + vB) + (vC + vB);
 	check_values_sum_4<float,vtype,A,B,C>(vd);
 
-	vd.getV<A>() = vd.getV<B>() - (vd.getV<C>() + vd.getV<B>());
+	vA = vB - (vC + vB);
 	check_values_sub_31<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) - vd.getV<B>();
+	vA = (vC + vB) - vB;
 	check_values_sub_32<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) - (vd.getV<C>() + vd.getV<B>());
+	vA = (vC + vB) - (vC + vB);
 	check_values_sub_4<float,vtype,A,B,C>(vd);
 
-	vd.getV<A>() = vd.getV<B>() * (vd.getV<C>() + vd.getV<B>());
+	vA = vB * (vC + vB);
 	check_values_mul_3<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) * vd.getV<B>();
+	vA = (vC + vB) * vB;
 	check_values_mul_3<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) * (vd.getV<C>() + vd.getV<B>());
+	vA = (vC + vB) * (vC + vB);
 	check_values_mul_4<float,vtype,A,B,C>(vd);
 
-	vd.getV<A>() = vd.getV<B>() / (vd.getV<C>() + vd.getV<B>());
+	vA = vB / (vC + vB);
 	check_values_div_31<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) / vd.getV<B>();
+	vA = (vC + vB) / vB;
 	check_values_div_32<float,vtype,A,B,C>(vd);
-	vd.getV<A>() = (vd.getV<C>() + vd.getV<B>()) / (vd.getV<C>() + vd.getV<B>());
+	vA = (vC + vB) / (vC + vB);
 	check_values_div_4<float,vtype,A,B,C>(vd);
 
 	// We try with vectors
 
 	// Various combination of 2 operator
 
-	vd.getV<PA>() = vd.getV<PB>() + 2.0;
-	check_values_sum<VectorS<3,float>,vtype,PA,PB,PC>(vd,2.0);
-	vd.getV<PA>() = 2.0 + vd.getV<PB>();
-	check_values_sum<VectorS<3,float>,vtype,PA,PB,PC>(vd,2.0);
-	vd.getV<PA>() = vd.getV<PC>() + vd.getV<PB>();
-	check_values_sum<VectorS<3,float>,vtype,PA,PB,PC>(vd,vd);
-
-	vd.getV<PA>() = vd.getV<PB>() - 2.0;
-	check_values_sub<VectorS<3,float>,vtype,PA,PB,PC>(vd,2.0);
-	vd.getV<PA>() = 2.0 - vd.getV<PB>();
-	check_values_sub<VectorS<3,float>,vtype,PA,PB,PC>(2.0,vd);
-	vd.getV<PA>() = vd.getV<PC>() - vd.getV<PB>();
-	check_values_sub<VectorS<3,float>,vtype,PA,PB,PC>(vd,vd);
-
-	vd.getV<PA>() = vd.getV<PB>() * 2.0;
-	check_values_mul<VectorS<3,float>,vtype,PA,PB,PC>(vd,2.0);
-	vd.getV<PA>() = 2.0 * vd.getV<PB>();
-	check_values_mul<VectorS<3,float>,vtype,PA,PB,PC>(vd,2.0);
-	vd.getV<PA>() = vd.getV<PC>() * vd.getV<PB>();
-	check_values_mul<VectorS<3,float>,vtype,PA,PB,PC>(vd,vd);
-
-	vd.getV<PA>() = vd.getV<PB>() / 2.0;
-	check_values_div<VectorS<3,float>,vtype,PA,PB,PC>(vd,2.0);
-	vd.getV<PA>() = 2.0 / vd.getV<PB>();
-	check_values_div<VectorS<3,float>,vtype,PA,PB,PC>(2.0,vd);
-	vd.getV<PA>() = vd.getV<PC>() / vd.getV<PB>();
-	check_values_div<VectorS<3,float>,vtype,PA,PB,PC>(vd,vd);
+	vVA = vVB + 2.0f;
+	check_values_sum<VectorS<3,float>,vtype,VA,VB,VC>(vd,2.0f);
+	vVA = 2.0f + vVB;
+	check_values_sum<VectorS<3,float>,vtype,VA,VB,VC>(vd,2.0f);
+	vVA = vVC + vVB;
+	check_values_sum<VectorS<3,float>,vtype,VA,VB,VC>(vd,vd);
+
+	vVA = vVB - 2.0f;
+	check_values_sub<VectorS<3,float>,vtype,VA,VB,VC>(vd,2.0f);
+	vVA = 2.0f - vVB;
+	check_values_sub<VectorS<3,float>,vtype,VA,VB,VC>(2.0f,vd);
+	vVA = vVC - vVB;
+	check_values_sub<VectorS<3,float>,vtype,VA,VB,VC>(vd,vd);
+
+	vVA = vVB * 2.0f;
+	check_values_mul<VectorS<3,float>,vtype,VA,VB,VC>(vd,2.0f);
+	vVA = 2.0f * vVB;
+	check_values_mul<VectorS<3,float>,vtype,VA,VB,VC>(vd,2.0f);
+	vVA = vVC * vVB;
+	check_values_mul<VectorS<3,float>,vtype,VA,VB,VC>(vd,vd);
+
+	vVA = vVB / 2.0f;
+	check_values_div<VectorS<3,float>,vtype,VA,VB,VC>(vd,2.0f);
+	vVA = 2.0f / vVB;
+	check_values_div<VectorS<3,float>,vtype,VA,VB,VC>(2.0f,vd);
+	vVA = vVC / vVB;
+	check_values_div<VectorS<3,float>,vtype,VA,VB,VC>(vd,vd);
 
 	// Variuos combination 3 operator
 
-	vd.getV<PA>() = vd.getV<PB>() + (vd.getV<PC>() + vd.getV<PB>());
-	check_values_sum_3<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) + vd.getV<PB>();
-	check_values_sum_3<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) + (vd.getV<PC>() + vd.getV<PB>());
-	check_values_sum_4<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-
-	vd.getV<PA>() = vd.getV<PB>() - (vd.getV<PC>() + vd.getV<PB>());
-	check_values_sub_31<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) - vd.getV<PB>();
-	check_values_sub_32<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) - (vd.getV<PC>() + vd.getV<PB>());
-	check_values_sub_4<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-
-	vd.getV<PA>() = vd.getV<PB>() * (vd.getV<PC>() + vd.getV<PB>());
-	check_values_mul_3<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) * vd.getV<PB>();
-	check_values_mul_3<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) * (vd.getV<PC>() + vd.getV<PB>());
-	check_values_mul_4<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<A>() = vd.getV<PB>() * (vd.getV<PC>() + vd.getV<PB>());
-	check_values_mul_3<float,vtype,A,PB,PC>(vd);
-	vd.getV<A>() = (vd.getV<PC>() + vd.getV<PB>()) * vd.getV<PB>();
-	check_values_mul_3<float,vtype,A,PB,PC>(vd);
-	vd.getV<A>() = (vd.getV<PC>() + vd.getV<PB>()) * (vd.getV<PC>() + vd.getV<PB>());
-	check_values_mul_4<float,vtype,A,PB,PC>(vd);
-
-	vd.getV<PA>() = vd.getV<PB>() / (vd.getV<PC>() + vd.getV<PB>());
-	check_values_div_31<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) / vd.getV<PB>();
-	check_values_div_32<VectorS<3,float>,vtype,PA,PB,PC>(vd);
-	vd.getV<PA>() = (vd.getV<PC>() + vd.getV<PB>()) / (vd.getV<PC>() + vd.getV<PB>());
-	check_values_div_4<VectorS<3,float>,vtype,PA,PB,PC>(vd);
+	vVA = vVB + (vVC + vVB);
+	check_values_sum_3<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) + vVB;
+	check_values_sum_3<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) + (vVC + vVB);
+	check_values_sum_4<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+
+	vVA = vVB - (vVC + vVB);
+	check_values_sub_31<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) - vVB;
+	check_values_sub_32<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) - (vVC + vVB);
+	check_values_sub_4<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+
+	vVA = vVB * (vVC + vVB);
+	check_values_mul_3<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) * vVB;
+	check_values_mul_3<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) * (vVC + vVB);
+	check_values_mul_4<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vA = vVB * (vVC + vVB);
+	check_values_mul_3<float,vtype,A,VB,VC>(vd);
+	vA = (vVC + vVB) * vVB;
+	check_values_mul_3<float,vtype,A,VB,VC>(vd);
+	vA = (vVC + vVB) * (vVC + vVB);
+	check_values_mul_4<float,vtype,A,VB,VC>(vd);
+
+	vVA = vVB / (vVC + vVB);
+	check_values_div_31<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) / vVB;
+	check_values_div_32<VectorS<3,float>,vtype,VA,VB,VC>(vd);
+	vVA = (vVC + vVB) / (vVC + vVB);
+	check_values_div_4<VectorS<3,float>,vtype,VA,VB,VC>(vd);
 
 	// normalization function
 
-	vd.getV<A>() = vd.getV<PB>() * vd.getV<PC>() + norm(vd.getV<PC>() + vd.getV<PB>()) + distance(vd.getV<PC>(),vd.getV<PB>());
+	vA = vVB * vVC + norm(vVC + vVB) + distance(vVC,vVB);
 	check_values_scal_norm_dist(vd);
-
-	// we apply an exponential kernel to calculate something
-
-	auto cl = vd.getCellList(0.01);
-	exp_kernel ker(0.2);
-
-	vd.getV<A>() = applyKernel(vd.getV<PC>() * vd.getV<PB>() + norm(vd.getV<PB>()),vd,cl,ker) + vd.getV<C>();
-	check_values_apply_kernel(vd);
 }
 
-BOOST_AUTO_TEST_SUITE_END()
+#include "vector_dist_operators_apply_kernel_unit_tests.hpp"
 
+BOOST_AUTO_TEST_SUITE_END()
 
 
 #endif /* OPENFPM_NUMERICS_SRC_OPERATORS_VECTOR_VECTOR_DIST_OPERATORS_UNIT_TESTS_HPP_ */
-- 
GitLab