test_normal.cpp 13.3 KB
Newer Older
Vincent Rabaud's avatar
Vincent Rabaud committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35
/*
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2012, Willow Garage, Inc.
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of Willow Garage, Inc. nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *
 */

36
#include "test_precomp.hpp"
Vincent Rabaud's avatar
Vincent Rabaud committed
37 38
#include <opencv2/rgbd.hpp>

39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
namespace cv
{
namespace rgbd
{

class CV_EXPORTS TickMeter
{
public:
    TickMeter();
    void start();
    void stop();

    int64 getTimeTicks() const;
    double getTimeMicro() const;
    double getTimeMilli() const;
    double getTimeSec()   const;
    int64 getCounter() const;

    void reset();
private:
    int64 counter;
    int64 sumTime;
    int64 startTime;
};

TickMeter::TickMeter() { reset(); }
int64 TickMeter::getTimeTicks() const { return sumTime; }
double TickMeter::getTimeSec()   const { return (double)getTimeTicks()/getTickFrequency(); }
double TickMeter::getTimeMilli() const { return getTimeSec()*1e3; }
double TickMeter::getTimeMicro() const { return getTimeMilli()*1e3; }
int64 TickMeter::getCounter() const { return counter; }
void  TickMeter::reset() {startTime = 0; sumTime = 0; counter = 0; }

void TickMeter::start(){ startTime = getTickCount(); }
void TickMeter::stop()
{
    int64 time = getTickCount();
    if ( startTime == 0 )
        return;

    ++counter;
    
    sumTime += ( time - startTime );
    startTime = 0;
}
Vincent Rabaud's avatar
Vincent Rabaud committed
84

85 86
Point3f
rayPlaneIntersection(Point2f uv, const Mat& centroid, const Mat& normal, const Mat_<float>& Kinv);
Vincent Rabaud's avatar
Vincent Rabaud committed
87

88 89 90 91 92
Vec3f
rayPlaneIntersection(const Vec3d& uv1, double centroid_dot_normal, const Vec3d& normal,
                     const Matx33d& Kinv);
Vec3f
rayPlaneIntersection(const Vec3d& uv1, double centroid_dot_normal, const Vec3d& normal, const Matx33d& Kinv)
Vincent Rabaud's avatar
Vincent Rabaud committed
93 94
{

95
  Matx31d L = Kinv * uv1; //a ray passing through camera optical center
Vincent Rabaud's avatar
Vincent Rabaud committed
96
  //and uv.
97
  L = L * (1.0 / norm(L));
Vincent Rabaud's avatar
Vincent Rabaud committed
98 99 100 101 102 103 104 105 106 107
  double LdotNormal = L.dot(normal);
  double d;
  if (std::fabs(LdotNormal) > 1e-9)
  {
    d = centroid_dot_normal / LdotNormal;
  }
  else
  {
    d = 1.0;
    std::cout << "warning, LdotNormal nearly 0! " << LdotNormal << std::endl;
108
    std::cout << "contents of L, Normal: " << Mat(L) << ", " << Mat(normal) << std::endl;
Vincent Rabaud's avatar
Vincent Rabaud committed
109
  }
110
  Vec3f xyz((float)(d * L(0)), (float)(d * L(1)), (float)(d * L(2)));
Vincent Rabaud's avatar
Vincent Rabaud committed
111 112 113
  return xyz;
}

114 115
Point3f
rayPlaneIntersection(Point2f uv, const Mat& centroid, const Mat& normal, const Mat_<float>& Kinv)
Vincent Rabaud's avatar
Vincent Rabaud committed
116
{
117 118 119
  Matx33d dKinv(Kinv);
  Vec3d dNormal(normal);
  return rayPlaneIntersection(Vec3d(uv.x, uv.y, 1), centroid.dot(normal), dNormal, dKinv);
Vincent Rabaud's avatar
Vincent Rabaud committed
120 121 122 123 124 125 126 127 128
}

const int W = 640;
const int H = 480;
int window_size = 5;
float focal_length = 525;
float cx = W / 2.f + 0.5f;
float cy = H / 2.f + 0.5f;

129 130
Mat K = (Mat_<double>(3, 3) << focal_length, 0, cx, 0, focal_length, cy, 0, 0, 1);
Mat Kinv = K.inv();
Vincent Rabaud's avatar
Vincent Rabaud committed
131

132
static RNG rng;
Vincent Rabaud's avatar
Vincent Rabaud committed
133 134 135
struct Plane
{

136
  Vec3d n, p;
Vincent Rabaud's avatar
Vincent Rabaud committed
137 138 139 140 141 142
  double p_dot_n;
  Plane()
  {
    n[0] = rng.uniform(-0.5, 0.5);
    n[1] = rng.uniform(-0.5, 0.5);
    n[2] = -0.3; //rng.uniform(-1.f, 0.5f);
143
    n = n / norm(n);
Ilya Lavrenov's avatar
Ilya Lavrenov committed
144
    set_d((float)rng.uniform(-2.0, 0.6));
Vincent Rabaud's avatar
Vincent Rabaud committed
145 146 147 148 149
  }

  void
  set_d(float d)
  {
150
    p = Vec3d(0, 0, d / n[2]);
Vincent Rabaud's avatar
Vincent Rabaud committed
151 152 153
    p_dot_n = p.dot(n);
  }

154 155
  Vec3f
  intersection(float u, float v, const Matx33f& Kinv_in) const
Vincent Rabaud's avatar
Vincent Rabaud committed
156
  {
157
    return rayPlaneIntersection(Vec3d(u, v, 1), p_dot_n, n, Kinv_in);
Vincent Rabaud's avatar
Vincent Rabaud committed
158 159 160 161
  }
};

void
162
gen_points_3d(std::vector<Plane>& planes_out, Mat_<unsigned char> &plane_mask, Mat& points3d, Mat& normals,
Vincent Rabaud's avatar
Vincent Rabaud committed
163 164
              int n_planes);
void
165
gen_points_3d(std::vector<Plane>& planes_out, Mat_<unsigned char> &plane_mask, Mat& points3d, Mat& normals,
Vincent Rabaud's avatar
Vincent Rabaud committed
166 167 168 169 170 171 172 173 174 175 176 177
              int n_planes)
{
  std::vector<Plane> planes;
  for (int i = 0; i < n_planes; i++)
  {
    Plane px;
    for (int j = 0; j < 1; j++)
    {
      px.set_d(rng.uniform(-3.f, -0.5f));
      planes.push_back(px);
    }
  }
178 179
  Mat_ < Vec3f > outp(H, W);
  Mat_ < Vec3f > outn(H, W);
Vincent Rabaud's avatar
Vincent Rabaud committed
180 181 182 183 184 185 186 187 188 189 190
  plane_mask.create(H, W);

  // n  ( r - r_0) = 0
  // n * r_0 = d
  //
  // r_0 = (0,0,0)
  // r[0]
  for (int v = 0; v < H; v++)
  {
    for (int u = 0; u < W; u++)
    {
Ilya Lavrenov's avatar
Ilya Lavrenov committed
191
      unsigned int plane_index = (unsigned int)((u / float(W)) * planes.size());
Vincent Rabaud's avatar
Vincent Rabaud committed
192
      Plane plane = planes[plane_index];
Ilya Lavrenov's avatar
Ilya Lavrenov committed
193
      outp(v, u) = plane.intersection((float)u, (float)v, Kinv);
Vincent Rabaud's avatar
Vincent Rabaud committed
194
      outn(v, u) = plane.n;
Ilya Lavrenov's avatar
Ilya Lavrenov committed
195
      plane_mask(v, u) = (uchar)plane_index;
Vincent Rabaud's avatar
Vincent Rabaud committed
196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219
    }
  }
  planes_out = planes;
  points3d = outp;
  normals = outn;
}

////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

class CV_RgbdNormalsTest: public cvtest::BaseTest
{
public:
  CV_RgbdNormalsTest()
  {
  }
  ~CV_RgbdNormalsTest()
  {
  }
protected:
  void
  run(int)
  {
    try
    {
220
      Mat_<unsigned char> plane_mask;
Vincent Rabaud's avatar
Vincent Rabaud committed
221 222
      for (unsigned char i = 0; i < 3; ++i)
      {
223
        RgbdNormals::RGBD_NORMALS_METHOD method;
Vincent Rabaud's avatar
Vincent Rabaud committed
224 225 226 227 228 229 230 231
        // inner vector: whether it's 1 plane or 3 planes
        // outer vector: float or double
        std::vector<std::vector<float> > errors(2);
        errors[0].resize(2);
        errors[1].resize(2);
        switch (i)
        {
          case 0:
232
            method = RgbdNormals::RGBD_NORMALS_METHOD_FALS;
Vincent Rabaud's avatar
Vincent Rabaud committed
233
            std::cout << std::endl << "*** FALS" << std::endl;
234 235 236 237
            errors[0][0] = 0.006f;
            errors[0][1] = 0.03f;
            errors[1][0] = 0.00008f;
            errors[1][1] = 0.02f;
Vincent Rabaud's avatar
Vincent Rabaud committed
238 239
            break;
          case 1:
240
            method = RgbdNormals::RGBD_NORMALS_METHOD_LINEMOD;
Vincent Rabaud's avatar
Vincent Rabaud committed
241
            std::cout << std::endl << "*** LINEMOD" << std::endl;
242 243 244 245
            errors[0][0] = 0.04f;
            errors[0][1] = 0.07f;
            errors[1][0] = 0.05f;
            errors[1][1] = 0.08f;
Vincent Rabaud's avatar
Vincent Rabaud committed
246 247
            break;
          case 2:
248
            method = RgbdNormals::RGBD_NORMALS_METHOD_SRI;
Vincent Rabaud's avatar
Vincent Rabaud committed
249
            std::cout << std::endl << "*** SRI" << std::endl;
250 251 252 253
            errors[0][0] = 0.02f;
            errors[0][1] = 0.04f;
            errors[1][0] = 0.02f;
            errors[1][1] = 0.04f;
Vincent Rabaud's avatar
Vincent Rabaud committed
254
            break;
Ilya Lavrenov's avatar
Ilya Lavrenov committed
255
		  default:
256
			method = (RgbdNormals::RGBD_NORMALS_METHOD)-1;
Ilya Lavrenov's avatar
Ilya Lavrenov committed
257
			CV_Error(0, "");
Vincent Rabaud's avatar
Vincent Rabaud committed
258 259 260 261 262 263 264 265 266 267
        }

        for (unsigned char j = 0; j < 2; ++j)
        {
          int depth = (j % 2 == 0) ? CV_32F : CV_64F;
          if (depth == CV_32F)
            std::cout << "* float" << std::endl;
          else
            std::cout << "* double" << std::endl;

268
          RgbdNormals normals_computer(H, W, depth, K, 5, method);
Vincent Rabaud's avatar
Vincent Rabaud committed
269 270 271
          normals_computer.initialize();

          std::vector<Plane> plane_params;
272
          Mat points3d, ground_normals;
Vincent Rabaud's avatar
Vincent Rabaud committed
273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306
          // 1 plane, continuous scene, very low error..
          std::cout << "1 plane" << std::endl;
          float err_mean = 0;
          for (int ii = 0; ii < 5; ++ii)
          {
            gen_points_3d(plane_params, plane_mask, points3d, ground_normals, 1);
            err_mean += testit(points3d, ground_normals, normals_computer);
          }
          std::cout << "mean diff: " << (err_mean / 5) << std::endl;
          EXPECT_LE(err_mean/5, errors[j][0])<< " thresh: " << errors[j][0] << std::endl;

          // 3 discontinuities, more error expected.
          std::cout << "3 planes" << std::endl;
          err_mean = 0;
          for (int ii = 0; ii < 5; ++ii)
          {
            gen_points_3d(plane_params, plane_mask, points3d, ground_normals, 3);
            err_mean += testit(points3d, ground_normals, normals_computer);
          }
          std::cout << "mean diff: " << (err_mean / 5) << std::endl;
          EXPECT_LE(err_mean/5, errors[j][1])<< "mean diff: " << (err_mean/5) << " thresh: " << errors[j][1] << std::endl;
        }
      }

      //TODO test NaNs in data

    } catch (...)
    {
      ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
    }
    ts->set_failed_test_info(cvtest::TS::OK);
  }

  float
307
  testit(const Mat & points3d, const Mat & in_ground_normals, const RgbdNormals & normals_computer)
Vincent Rabaud's avatar
Vincent Rabaud committed
308
  {
309
    TickMeter tm;
Vincent Rabaud's avatar
Vincent Rabaud committed
310
    tm.start();
311
    Mat in_normals;
312
    if (normals_computer.getMethod() == RgbdNormals::RGBD_NORMALS_METHOD_LINEMOD)
Vincent Rabaud's avatar
Vincent Rabaud committed
313
    {
314 315
      std::vector<Mat> channels;
      split(points3d, channels);
Vincent Rabaud's avatar
Vincent Rabaud committed
316 317 318 319 320 321
      normals_computer(channels[2], in_normals);
    }
    else
      normals_computer(points3d, in_normals);
    tm.stop();

322
    Mat_<Vec3f> normals, ground_normals;
Vincent Rabaud's avatar
Vincent Rabaud committed
323 324 325 326 327 328 329
    in_normals.convertTo(normals, CV_32FC3);
    in_ground_normals.convertTo(ground_normals, CV_32FC3);

    float err = 0;
    for (int y = 0; y < normals.rows; ++y)
      for (int x = 0; x < normals.cols; ++x)
      {
330 331 332
        Vec3f vec1 = normals(y, x), vec2 = ground_normals(y, x);
        vec1 = vec1 / norm(vec1);
        vec2 = vec2 / norm(vec2);
Vincent Rabaud's avatar
Vincent Rabaud committed
333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362

        float dot = vec1.dot(vec2);
        // Just for rounding errors
        if (std::abs(dot) < 1)
          err += std::min(std::acos(dot), std::acos(-dot));
      }

    err /= normals.rows * normals.cols;
    std::cout << "Average error: " << err << " Speed: " << tm.getTimeMilli() << " ms" << std::endl;
    return err;
  }
};

////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

class CV_RgbdPlaneTest: public cvtest::BaseTest
{
public:
  CV_RgbdPlaneTest()
  {
  }
  ~CV_RgbdPlaneTest()
  {
  }
protected:
  void
  run(int)
  {
    try
    {
363
      RgbdPlane plane_computer;
Vincent Rabaud's avatar
Vincent Rabaud committed
364 365

      std::vector<Plane> planes;
366 367
      Mat points3d, ground_normals;
      Mat_<unsigned char> plane_mask;
Vincent Rabaud's avatar
Vincent Rabaud committed
368 369 370 371 372 373 374 375 376 377 378 379 380 381 382
      gen_points_3d(planes, plane_mask, points3d, ground_normals, 1);
      testit(planes, plane_mask, points3d, plane_computer); // 1 plane, continuous scene, very low error..
      for (int ii = 0; ii < 10; ii++)
      {
        gen_points_3d(planes, plane_mask, points3d, ground_normals, 3); //three planes
        testit(planes, plane_mask, points3d, plane_computer); // 3 discontinuities, more error expected.
      }
    } catch (...)
    {
      ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
    }
    ts->set_failed_test_info(cvtest::TS::OK);
  }

  void
383 384
  testit(const std::vector<Plane> & gt_planes, const Mat & gt_plane_mask, const Mat & points3d,
         RgbdPlane & plane_computer)
Vincent Rabaud's avatar
Vincent Rabaud committed
385 386 387
  {
    for (char i_test = 0; i_test < 2; ++i_test)
    {
388 389 390
      TickMeter tm1, tm2;
      Mat plane_mask;
      std::vector<Vec4f> plane_coefficients;
Vincent Rabaud's avatar
Vincent Rabaud committed
391 392 393 394 395 396

      if (i_test == 0)
      {
        tm1.start();
        // First, get the normals
        int depth = CV_32F;
397 398
        RgbdNormals normals_computer(H, W, depth, K, 5, RgbdNormals::RGBD_NORMALS_METHOD_FALS);
        Mat normals;
Vincent Rabaud's avatar
Vincent Rabaud committed
399 400 401 402 403 404 405 406 407 408 409 410 411 412 413
        normals_computer(points3d, normals);
        tm1.stop();

        tm2.start();
        plane_computer(points3d, normals, plane_mask, plane_coefficients);
        tm2.stop();
      }
      else
      {
        tm2.start();
        plane_computer(points3d, plane_mask, plane_coefficients);
        tm2.stop();
      }

      // Compare each found plane to each ground truth plane
414 415
      int n_planes = (int)plane_coefficients.size();
      int n_gt_planes = (int)gt_planes.size();
416
      Mat_<int> matching(n_gt_planes, n_planes);
417
      for (int j = 0; j < n_gt_planes; ++j)
Vincent Rabaud's avatar
Vincent Rabaud committed
418
      {
419 420
        Mat gt_mask = gt_plane_mask == j;
        int n_gt = countNonZero(gt_mask);
Vincent Rabaud's avatar
Vincent Rabaud committed
421
        int n_max = 0, i_max = 0;
422
        for (int i = 0; i < n_planes; ++i)
Vincent Rabaud's avatar
Vincent Rabaud committed
423
        {
424 425 426
          Mat dst;
          bitwise_and(gt_mask, plane_mask == i, dst);
          matching(j, i) = countNonZero(dst);
Vincent Rabaud's avatar
Vincent Rabaud committed
427 428 429 430 431 432 433 434 435
          if (matching(j, i) > n_max)
          {
            n_max = matching(j, i);
            i_max = i;
          }
        }
        // Get the best match
        ASSERT_LE(float(n_max - n_gt) / n_gt, 0.001);
        // Compare the normals
436
        Vec3d normal(plane_coefficients[i_max][0], plane_coefficients[i_max][1], plane_coefficients[i_max][2]);
Vincent Rabaud's avatar
Vincent Rabaud committed
437 438 439 440 441 442 443 444 445 446 447
        ASSERT_GE(std::abs(gt_planes[j].n.dot(normal)), 0.95);
      }

      std::cout << " Speed: ";
      if (i_test == 0)
        std::cout << "normals " << tm1.getTimeMilli() << " ms and ";
      std::cout << "plane " << tm2.getTimeMilli() << " ms " << std::endl;
    }
  }
};

448 449 450
}
}

Vincent Rabaud's avatar
Vincent Rabaud committed
451 452 453 454
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

TEST(Rgbd_Normals, compute)
{
455
  cv::rgbd::CV_RgbdNormalsTest test;
Vincent Rabaud's avatar
Vincent Rabaud committed
456 457 458 459 460
  test.safe_run();
}

TEST(Rgbd_Plane, compute)
{
461
  cv::rgbd::CV_RgbdPlaneTest test;
Vincent Rabaud's avatar
Vincent Rabaud committed
462 463
  test.safe_run();
}