test_utils.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00037 #include <gtest/gtest.h>
00038 #include <spline_smoother/spline_smoother_utils.h>
00039 #include <stdlib.h>
00040 
00041 static double getRandomNumber(double min, double max)
00042 {
00043   return ((double)rand() / RAND_MAX)*(max-min) + min;
00044 }
00045 
00046 TEST(TestUtils, testTridiagonalSolver)
00047 {
00048   // seed the random number generator:
00049   srand(2);
00050 
00051   // generate a random tridiagonal matrix:
00052   int n=10;
00053 
00054   std::vector<double> a(n);
00055   std::vector<double> b(n);
00056   std::vector<double> c(n);
00057   std::vector<double> d(n);
00058   std::vector<double> x(n);
00059   std::vector<double> solved_x(n);
00060 
00061   for (int i=0; i<n; i++)
00062   {
00063     a[i] = getRandomNumber(10.0, 20.0);
00064     b[i] = getRandomNumber(1.0, 4.0);
00065     c[i] = getRandomNumber(1.0, 4.0);
00066     x[i] = getRandomNumber(-1.0, 1.0);
00067   }
00068   a[0] = 0.0;
00069   c[n-1] = 0.0;
00070 
00071   // multiply to get values for d:
00072   for (int i=1; i<n-1; i++)
00073   {
00074     d[i] = a[i]*x[i-1] + b[i]*x[i] + c[i]*x[i+1];
00075   }
00076   d[0] = b[0]*x[0] + c[0]*x[1];
00077   d[n-1] = a[n-1]*x[n-2] + b[n-1]*x[n-1];
00078 
00079   // solve it:
00080   spline_smoother::tridiagonalSolve(a, b, c, d, solved_x);
00081 
00082   double tolerance = 1e-8;
00083 
00084   // check it:
00085   for (int i=0; i<n; i++)
00086   {
00087     EXPECT_NEAR(x[i], solved_x[i], tolerance);
00088   }
00089 }
00090 
00091 TEST(TestUtils, testTridiagonalSolver2)
00092 {
00093   // seed the random number generator:
00094   srand(2);
00095 
00096   // generate a tridiagonal matrix for cubic splines
00097   int n=10;
00098 
00099   std::vector<double> a(n);
00100   std::vector<double> b(n);
00101   std::vector<double> c(n);
00102   std::vector<double> d(n);
00103   std::vector<double> x(n);
00104   std::vector<double> solved_x(n);
00105 
00106   for (int i=0; i<n; i++)
00107   {
00108     a[i] = 4.0;
00109     b[i] = 1.0;
00110     c[i] = 1.0;
00111     x[i] = getRandomNumber(-1.0, 1.0);
00112   }
00113   a[0] = 0.0;
00114   c[n-1] = 0.0;
00115   b[0] = 2.0;
00116   b[n-1] = 2.0;
00117 
00118   // multiply to get values for d:
00119   for (int i=1; i<n-1; i++)
00120   {
00121     d[i] = a[i]*x[i-1] + b[i]*x[i] + c[i]*x[i+1];
00122   }
00123   d[0] = b[0]*x[0] + c[0]*x[1];
00124   d[n-1] = a[n-1]*x[n-2] + b[n-1]*x[n-1];
00125 
00126   // solve it:
00127   spline_smoother::tridiagonalSolve(a, b, c, d, solved_x);
00128 
00129   double tolerance = 1e-8;
00130 
00131   // check it:
00132   for (int i=0; i<n; i++)
00133   {
00134     EXPECT_NEAR(x[i], solved_x[i], tolerance);
00135   }
00136 }


spline_smoother
Author(s): Mrinal Kalakrishnan / mail@mrinal.net
autogenerated on Mon Dec 2 2013 12:35:44