projection.cc 22.4 KB
Newer Older
Joseph Mirabel's avatar
Joseph Mirabel 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
36
37
38
39
40
41
42
43
// Copyright (c) 2014, LAAS-CNRS
// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
//
// This file is part of test-hpp.
// test-hpp is free software: you can redistribute it
// and/or modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation, either version
// 3 of the License, or (at your option) any later version.
//
// test-hpp is distributed in the hope that it will be
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
// General Lesser Public License for more details.  You should have
// received a copy of the GNU Lesser General Public License along with
// test-hpp. If not, see <http://www.gnu.org/licenses/>.

#include <algorithm>
#include <ctime>

#include <boost/accumulators/framework/accumulator_set.hpp>
#include <boost/accumulators/statistics/mean.hpp>
#include <boost/accumulators/statistics/stats.hpp>
#include <boost/accumulators/statistics/count.hpp>
#include <boost/accumulators/statistics/variance.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>

#include <Eigen/SVD>

#define ERROR_THRESHOLD 1e-4
#define MAX_ITERATIONS  20

#define NB_TRIES 100
#define RATE_WARNING 0.15

#define MESSAGE_INF(m) std::cout << m << std::endl
#define MESSAGE_WAR(m) std::cout << m << std::endl
#define MESSAGE_ERR(m) std::cerr << m << std::endl

#include <hpp/model/urdf/util.hh>
#include <hpp/model/device.hh>
#include <hpp/model/configuration.hh>
#include <hpp/constraints/relative-transformation.hh>
#include <hpp/wholebody-step/static-stability-constraint.hh>
44
#include <hpp/constraints/differentiable-function.hh>
Joseph Mirabel's avatar
Joseph Mirabel committed
45
46
47
48
49
50
51
52
53
54
#include <hpp/core/basic-configuration-shooter.hh>
#include <hpp/core/config-projector.hh>

#include <hpp/util/timer.hh>

using namespace boost::accumulators;
using hpp::model::Device;
using hpp::model::DevicePtr_t;
using hpp::model::JointPtr_t;
using hpp::core::DifferentiableFunctionPtr_t;
55
using hpp::core::NumericalConstraint;
56
using hpp::core::NumericalConstraintPtr_t;
Joseph Mirabel's avatar
Joseph Mirabel committed
57
using hpp::core::Constraint;
58
using hpp::core::ConstraintPtr_t;
Joseph Mirabel's avatar
Joseph Mirabel committed
59
60
61
62
63
64
65
66
67
68
69
70
using hpp::core::ConfigProjector;
using hpp::core::ConfigProjectorPtr_t;
using hpp::core::BasicConfigurationShooter;
using hpp::core::ConfigurationShooter;
using hpp::core::Configuration_t;
using hpp::core::ConfigurationOut_t;
using hpp::core::ConfigurationPtr_t;
using hpp::debug::Timer;

namespace hpp_test {
  DevicePtr_t robot;

71
  std::vector <std::vector <NumericalConstraintPtr_t> > functionSets;
Joseph Mirabel's avatar
Joseph Mirabel committed
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117

  template <typename T>
    void recursiveSubPartOf (const std::vector <T>& set, std::vector < std::vector <T> >& subparts) {
      typedef typename std::vector < T > Set_t;
      typedef std::vector < Set_t > Sets_t;
      if (set.size () == 0) {
        subparts.push_back (Set_t (0));
        return;
      }
      Set_t subset (set.size() - 1);
      for (size_t i = 0; i < subset.size(); i++)
        subset[i] = set[i+1];
      Sets_t subsetParts;
      recursiveSubPartOf <T> (subset, subsetParts);
      for (typename Sets_t::const_iterator it = subsetParts.begin ();
          it != subsetParts.end (); it++) {
        subparts.push_back (*it);
        subparts.push_back (*it);
        subparts.back ().push_back (set[0]);
      }
    }

  void loadHRP2 (DevicePtr_t robot) {
    hpp::model::urdf::loadRobotModel (
        robot,
        "freeflyer",
        "hrp2_14_description",
        "hrp2_14",
        "",
        "");
    robot->rootJoint ()->lowerBound (0, -1);
    robot->rootJoint ()->lowerBound (1, -1);
    robot->rootJoint ()->lowerBound (2, -1);
    robot->rootJoint ()->upperBound (0,  1);
    robot->rootJoint ()->upperBound (1,  1);
    robot->rootJoint ()->upperBound (2,  1);
    robot->rootJoint ()->isBounded (0, true);
    robot->rootJoint ()->isBounded (1, true);
    robot->rootJoint ()->isBounded (2, true);
  }

  void loadHRP2constraints (bool partOf = false) {
    /// Define the constraints
    JointPtr_t  leftAnkle = robot->getJointByName ("LLEG_JOINT5");
    JointPtr_t rightAnkle = robot->getJointByName ("RLEG_JOINT5");
    Configuration_t nc = robot->neutralConfiguration ();
118
119
120
    std::vector <NumericalConstraintPtr_t> funcs =
      hpp::wholebodyStep::createSlidingStabilityConstraint
      (robot, leftAnkle, rightAnkle, nc);
Joseph Mirabel's avatar
Joseph Mirabel committed
121
122
    functionSets.clear ();
    if (partOf)
123
      recursiveSubPartOf <NumericalConstraintPtr_t> (funcs, functionSets);
Joseph Mirabel's avatar
Joseph Mirabel committed
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
    else
      functionSets.push_back (funcs);
  }

  void loadPR2  (DevicePtr_t robot) {
    hpp::model::urdf::loadRobotModel (
        robot,
        "planar",
        "hpp_tutorial",
        "pr2",
        "",
        "");
    robot->rootJoint ()->lowerBound (0, -1);
    robot->rootJoint ()->lowerBound (1, -1);
    robot->rootJoint ()->upperBound (0,  1);
    robot->rootJoint ()->upperBound (1,  1);
    robot->rootJoint ()->isBounded (0, true);
    robot->rootJoint ()->isBounded (1, true);
  }

  void loadPR2constraints (bool partOf = false) {
    /// Define the constraints
    JointPtr_t  leftWrist = robot->getJointByBodyName ("l_gripper_tool_frame");
    JointPtr_t rightWrist = robot->getJointByBodyName ("r_gripper_tool_frame");
    Configuration_t nc = robot->neutralConfiguration ();
149
    std::vector <NumericalConstraintPtr_t> funcs;
Joseph Mirabel's avatar
Joseph Mirabel committed
150
    fcl::Transform3f transform; transform.setIdentity ();
151
152
153
    funcs.push_back (NumericalConstraint::create
		     (hpp::constraints::RelativeTransformation::create
		      (robot, leftWrist, rightWrist, transform)));
Joseph Mirabel's avatar
Joseph Mirabel committed
154
155
    functionSets.clear ();
    if (partOf)
156
      recursiveSubPartOf <NumericalConstraintPtr_t> (funcs, functionSets);
Joseph Mirabel's avatar
Joseph Mirabel committed
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
    else
      functionSets.push_back (funcs);
  }
}

namespace projection {
  struct Result {
    Configuration_t before, after;
    long long us;
    bool success;
    double error;
  };
  typedef std::vector <Result> ResultVector;
  typedef accumulator_set <double, stats<tag::variance> > Accumulator;

  void shootConfig (ResultVector& results, ConfigurationShooter* cs)
  {
    ConfigurationPtr_t cfg;
    for (size_t i = 0; i < results.size (); i++) {
      cfg = cs->shoot ();
      results[i].before = *cfg;
    }
  }

  void project (ConfigProjectorPtr_t cp, ResultVector& results, Accumulator& acc)
  {
    MESSAGE_INF ("Start " << results.size() << " projections...");
    for (size_t i = 0; i < results.size (); i++) {
      results[i].after = results[i].before;
      Timer t = Timer (true);
      results[i].success = cp->apply (results[i].after);
      t.stop ();
      results[i].us = t.duration ().total_microseconds ();
      results[i].error = cp->residualError ();

      if (!results[i].success) {
        acc (results[i].error);
      }
    }
  }

  int process () {
    int status = EXIT_SUCCESS;

    using hpp_test::functionSets;
    DevicePtr_t robot = hpp_test::robot;
    BasicConfigurationShooter bcs (robot);

    std::vector <ConfigProjectorPtr_t> cp;
    for (size_t i = 0; i < functionSets.size(); i++) {
      cp.push_back (ConfigProjector::create (robot, "", ERROR_THRESHOLD, MAX_ITERATIONS));
      for (size_t j = 0; j < functionSets[i].size(); j++)
209
        cp.back()->add (functionSets[i][j]);
Joseph Mirabel's avatar
Joseph Mirabel committed
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
    }
    MESSAGE_INF ("There are " << cp.size() << " projectors to be tested.");

    Accumulator acc;
    std::vector <Result> results (NB_TRIES);
    shootConfig (results, &bcs);

    for (size_t i = 0; i < cp.size (); i++) {
      acc = Accumulator ();
      project (cp[i], results, acc);

      if (count (acc) > 0) {
        if (count (acc) < RATE_WARNING * NB_TRIES) {
          MESSAGE_WAR ("----------------------------------------------------------");
          MESSAGE_WAR (*(cp[i]));
          MESSAGE_WAR ("Error rate: " << count (acc) << " / " << NB_TRIES);
          MESSAGE_WAR ("Residual error (mean, average): (" << mean (acc) << ", " << variance (acc) << ")");
          MESSAGE_WAR ("----------------------------------------------------------");
        } else {
          MESSAGE_ERR ("----------------------------------------------------------");
          MESSAGE_ERR (*(cp[i]));
          MESSAGE_ERR ("Error rate: " << count (acc) << " / " << NB_TRIES);
          MESSAGE_ERR ("Residual error (mean, average): (" << mean (acc) << ", " << variance (acc) << ")");
          //MESSAGE (cp[i]->statistics ());
          MESSAGE_ERR ("----------------------------------------------------------");
          status = EXIT_FAILURE;
        }
      }
    }
    return status;
  }

  namespace hrp2 {
    using hpp_test::loadHRP2;
    using hpp_test::loadHRP2constraints;
    int launch () {
      /// Create the robot
      DevicePtr_t robot = Device::create ("hrp2");
      hpp_test::robot = robot;
      loadHRP2 (robot);
      loadHRP2constraints (true);

      return process ();
    }
  }

  namespace pr2 {
    using hpp_test::loadPR2;
    using hpp_test::loadPR2constraints;
    int launch () {
      /// Create the robot
      DevicePtr_t robot = Device::create ("PR2");
      hpp_test::robot = robot;
      loadPR2 (robot);
      loadPR2constraints (true);

      return process ();
    }
  }
}

namespace svd {
  using namespace hpp_test;
  using namespace hpp::core;

  class SVDTest : public Constraint {
    public:
      vector_t offsetFromConfig (ConfigurationIn_t /* config */) {return vector_t ();}

279
      bool isSatisfied (ConfigurationIn_t config) {
Joseph Mirabel's avatar
Joseph Mirabel committed
280
281
282
283
        computeValueAndJacobian (config);
        return value_.squaredNorm () < squareErrorThreshold_;
      }

284
285
      bool isSatisfied (ConfigurationIn_t config, vector_t& error) {
	computeValueAndJacobian (config);
286
287
	error = value_;
	return value_.squaredNorm () < squareErrorThreshold_;
288
289
      }

290
      ConstraintPtr_t copy() const
Joseph Mirabel's avatar
Joseph Mirabel committed
291
      {
292
293
294
295
296
297
298
299
	abort ();
      }
      void addConstraint (const NumericalConstraintPtr_t& constraint)
      {
	DifferentiableFunctionPtr_t function = constraint->functionPtr ();
        size_ += function->outputSize ();
        vector_t value (function->outputSize ());
        matrix_t jacobian (function->outputSize (),
Joseph Mirabel's avatar
Joseph Mirabel committed
300
            robot_->numberDof ());
301
        constraints_.push_back (FunctionValueAndJacobian_t (function, value,
Joseph Mirabel's avatar
Joseph Mirabel committed
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
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
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
              jacobian));
        value_.resize (size_);
        Jacobian_.resize (size_, robot_->numberDof ());
      }

      bool impl_compute (ConfigurationOut_t config)
      {
        value_type alpha = .2;
        value_type alphaMax = .95;
        size_type errorDecreased = 3, iter = 0;
        value_type previousSquareNorm =
          std::numeric_limits<value_type>::infinity();
        // Fill value and Jacobian
        computeValueAndJacobian (config);
        squareNorm_ = value_.squaredNorm ();
        while (squareNorm_ > squareErrorThreshold_ && errorDecreased &&
            iter < maxIterations_) {
          doSVD ();
          vector_t v (-alpha * dq_);
          hpp::model::integrate (robot_, config, v, config);
          // Increase alpha towards alphaMax
          computeValueAndJacobian (config);
          alpha = alphaMax - .8*(alphaMax - alpha);
          squareNorm_ = value_.squaredNorm ();
          hppDout (info, "squareNorm = " << squareNorm_);
          --errorDecreased;
          if (squareNorm_ < previousSquareNorm) errorDecreased = 3;
          previousSquareNorm = squareNorm_;
          ++iter;
        };
        if (squareNorm_ > squareErrorThreshold_) {
          return false;
        }
        return true;
      }

      bool doSVD ()
      {
        std::vector <size_type> nonZeroCols, zeroCols;
        for (size_type iCol = 0; iCol < Jacobian_.cols (); iCol++) {
          if (Jacobian_.col (iCol).isZero ())
            zeroCols.push_back (iCol);
          else
            nonZeroCols.push_back (iCol);
        }
        reducedJacobian_.resize (size_, nonZeroCols.size ());
        for (size_t i = 0; i < nonZeroCols.size (); i++)
          reducedJacobian_.col (i) = Jacobian_.col (nonZeroCols[i]);
        Eigen::JacobiSVD <matrix_t> smallSVD (reducedJacobian_,
            Eigen::ComputeThinU | Eigen::ComputeThinV);
        dqSmall_ = smallSVD.solve(value_);

        dq_.setZero ();
        for (size_t i = 0; i < nonZeroCols.size (); i++)
          dq_ (nonZeroCols[i]) = dqSmall_ (i);

        return true;
      }

      bool doSVDWithCheck ()
      {
        Timer timeFull, timeSmall;
        timeFull.start ();
        Eigen::JacobiSVD <matrix_t> svd (Jacobian_,
            Eigen::ComputeThinU | Eigen::ComputeThinV);
        dq_ = svd.solve(value_);
        timeFull.stop ();

        timeSmall.start ();
        std::vector <size_type> nonZeroCols, zeroCols;
        for (size_type iCol = 0; iCol < Jacobian_.cols (); iCol++) {
          if (Jacobian_.col (iCol).isZero ())
            zeroCols.push_back (iCol);
          else
            nonZeroCols.push_back (iCol);
        }
        if ((size_type)(zeroCols.size () + nonZeroCols.size ()) != Jacobian_.cols ())
          MESSAGE_ERR ("Size are different.");
        reducedJacobian_.resize (size_, nonZeroCols.size ());
        for (size_t i = 0; i < nonZeroCols.size (); i++)
          reducedJacobian_.col (i) = Jacobian_.col (nonZeroCols[i]);
        Eigen::JacobiSVD <matrix_t> smallSVD (reducedJacobian_,
            Eigen::ComputeThinU | Eigen::ComputeThinV);
        dqSmall_ = smallSVD.solve(value_);

        timeSmall.stop ();

        vector_t dqZeroPart (zeroCols.size());
        vector_t dqNonZeroPart (nonZeroCols.size());
        for (size_t i = 0; i < nonZeroCols.size (); i++)
          dqNonZeroPart (i) = dq_ (nonZeroCols[i]);
        for (size_t i = 0; i < zeroCols.size (); i++) {
          dqZeroPart (i) = dq_ (zeroCols[i]);
          dq_ (zeroCols[i]) = 0;
        }

        if ((dqSmall_ - dqNonZeroPart).isZero () && dqZeroPart.isZero ()) {
          return true;
        }
        MESSAGE_INF ("Number of non-zero columns: " << nonZeroCols.size ());
        MESSAGE_INF ("Normal SVD time: " << timeFull.duration ());
        MESSAGE_INF ("Small  SVD time: " << timeSmall.duration ());
        if ((svd.nonzeroSingularValues () != smallSVD.nonzeroSingularValues ())
            || !(svd.singularValues () - smallSVD.singularValues ()).isZero ()) {
          MESSAGE_ERR ("Normal SVD (" << svd.nonzeroSingularValues () << ") " << svd.singularValues ().transpose ());
          MESSAGE_ERR ("Small  SVD (" << smallSVD.nonzeroSingularValues () << ") " << smallSVD.singularValues ().transpose ());
        }
        MESSAGE_INF ("Normal SVD dq zero part error: " << dqZeroPart.norm ());
        MESSAGE_INF ("Normal SVD dq: " << dqNonZeroPart.transpose ());
        MESSAGE_INF ("Small  SVD dq: " << dqSmall_.transpose ());
        return false;
      }

      SVDTest (const DevicePtr_t& robot, value_type errorThreshold, size_type maxIterations):
        Constraint ("SVDTest"), robot_ (robot), size_ (0),
        squareErrorThreshold_ (errorThreshold * errorThreshold),
        maxIterations_ (maxIterations), dq_ (robot_->numberDof ())
      {}

      std::ostream& print (std::ostream& os) const
      {
        os << "SVDTest contains";
        for (NumericalConstraints_t::const_iterator it = constraints_.begin ();
            it != constraints_.end (); it++) {
          const DifferentiableFunction& f (*(it->function));
          os << std::endl << f;
        }
        return os;
      }
      struct FunctionValueAndJacobian_t {
        FunctionValueAndJacobian_t (DifferentiableFunctionPtr_t f,
            vector_t v, matrix_t j): function (f),
        value (v),
        jacobian (j) {}

        DifferentiableFunctionPtr_t function;
        vector_t value;
        matrix_t jacobian;
      }; // struct FunctionValueAndJacobian_t
      typedef std::vector < FunctionValueAndJacobian_t > NumericalConstraints_t;
      void computeValueAndJacobian (ConfigurationIn_t configuration) {
        size_type row = 0, nbRows = 0;
        for (NumericalConstraints_t::iterator itConstraint =
            constraints_.begin ();
            itConstraint != constraints_.end (); itConstraint ++) {
          DifferentiableFunction& f = *(itConstraint->function);
          vector_t& value = itConstraint->value;
          matrix_t& jacobian = itConstraint->jacobian;
          f (value, configuration);
          f.jacobian (jacobian, configuration);
          nbRows = f.outputSize ();

          value_.segment (row, nbRows) = value;
          Jacobian_.middleRows (row, nbRows) = jacobian;
          row += nbRows;
        }
      }
      DevicePtr_t robot_;
      size_t size_;
      NumericalConstraints_t constraints_;
      value_type squareErrorThreshold_;
      value_type squareNorm_;
      size_type maxIterations_;
      mutable vector_t value_;
      mutable matrix_t Jacobian_;
      mutable vector_t dq_;

      mutable matrix_t reducedJacobian_;
      mutable vector_t dqSmall_;
471
  }; // class SVDTest
Joseph Mirabel's avatar
Joseph Mirabel committed
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487

  struct Result {
    Configuration_t before, after;
    bool success;
  };
  typedef std::vector <Result> ResultVector;

  void shootConfig (ResultVector& results, ConfigurationShooter* cs)
  {
    ConfigurationPtr_t cfg;
    for (size_t i = 0; i < results.size (); i++) {
      cfg = cs->shoot ();
      results[i].before = *cfg;
    }
  }

488
  size_t project (SVDTest* cp, ResultVector& results)
Joseph Mirabel's avatar
Joseph Mirabel committed
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
  {
    MESSAGE_INF ("Start " << results.size() << " projections...");
    size_t failCount = 0;
    for (size_t i = 0; i < results.size (); i++) {
      results[i].after = results[i].before;
      results[i].success = cp->apply (results[i].after);
      if (!results[i].success)
        failCount++;
    }
    return failCount;
  }

  int process () {
    int status = EXIT_SUCCESS;

    /// Create the robot
    DevicePtr_t robot = hpp_test::robot;
    BasicConfigurationShooter bcs (robot);
    using hpp_test::functionSets;

    std::vector <SVDTest*> cp;
    for (size_t i = 0; i < functionSets.size(); i++) {
      cp.push_back (new SVDTest (robot, ERROR_THRESHOLD, MAX_ITERATIONS));
      for (size_t j = 0; j < functionSets[i].size(); j++)
        cp.back()->addConstraint (functionSets[i][j]);
    }
    MESSAGE_INF ("There are " << cp.size() << " SVDTest to be tested.");

    std::vector <Result> results (NB_TRIES);
    shootConfig (results, &bcs);

    for (size_t i = 0; i < cp.size (); i++) {
521
      std::size_t f = project (cp[i], results);
Joseph Mirabel's avatar
Joseph Mirabel committed
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620

      if (f > 0) {
        MESSAGE_ERR ("----------------------------------------------------------");
        MESSAGE_ERR (*(cp[i]));
        MESSAGE_ERR ("Error rate: " << f << " / " << NB_TRIES);
        MESSAGE_ERR ("----------------------------------------------------------");
        status = EXIT_FAILURE;
      }
    }
    return status;
  }

  namespace hrp2 {
    int launch () {
      /// Create the robot
      DevicePtr_t robot = Device::create ("hrp2");
      hpp_test::robot = robot;
      loadHRP2 (robot);
      loadHRP2constraints (true);

      return process ();
    }
  }

  namespace pr2 {
    int launch () {
      /// Create the robot
      DevicePtr_t robot = Device::create ("PR2");
      hpp_test::robot = robot;
      loadPR2 (robot);
      loadPR2constraints (true);

      return process ();
    }
  }
}

namespace shuffle {
  struct Result {
    Configuration_t before, after;
    bool success;
    double error;
  };

  typedef std::vector <Result> ResultVector;
  typedef accumulator_set <double, stats<tag::variance> > Accumulator;

  void shootConfig (ResultVector& results, ConfigurationShooter* cs)
  {
    ConfigurationPtr_t cfg;
    for (size_t i = 0; i < results.size (); i++) {
      cfg = cs->shoot ();
      results[i].before = *cfg;
    }
  }

  void project (const std::vector <ConfigProjectorPtr_t>& cp, Result& r, Accumulator& acc)
  {
    MESSAGE_INF ("Start " << cp.size() << " projections...");
    bool shouldFail = false;
    Configuration_t ref (r.before.size ());
    r.after = r.before;
    r.success = cp[0]->apply (r.after);
    if (!r.success) {
      MESSAGE_ERR ("Projection failed!");
      shouldFail = true;
      return;
    }
    ref = r.after;

    for (size_t i = 1; i < cp.size (); i++) {
      r.after = r.before;
      r.success = cp[i]->apply (r.after);
      r.error = cp[i]->residualError ();

      if (shouldFail) {
        if (r.success)
          acc (r.error);
      } else {
        if (!r.success) {
          acc (r.error);
        } else if (!(r.after - ref).isZero ()) {
          MESSAGE_ERR ("Result differs: " << (r.after - ref).transpose ());
          acc (r.error);
        }
      }
    }
  }

  int process () {
    int status = EXIT_SUCCESS;
    std::srand (unsigned (std::time (0)));

    /// Create the robot
    DevicePtr_t robot = hpp_test::robot;
    BasicConfigurationShooter bcs (robot);
    using hpp_test::functionSets;

    std::vector <ConfigProjectorPtr_t> cp;
621
    std::vector <NumericalConstraintPtr_t> dfs = functionSets.front ();
Joseph Mirabel's avatar
Joseph Mirabel committed
622
623
624
    for (size_t i = 0; i < 10; i++) {
      cp.push_back (ConfigProjector::create (robot, "", ERROR_THRESHOLD, MAX_ITERATIONS));
      for (size_t j = 0; j < dfs.size(); j++)
625
        cp.back()->add (dfs[j]);
Joseph Mirabel's avatar
Joseph Mirabel committed
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
      std::random_shuffle (dfs.begin (), dfs.end ());
    }
    MESSAGE_INF ("There are " << cp.size() << " ConfigProjector to be tested.");

    std::vector <Result> results (NB_TRIES);
    shootConfig (results, &bcs);

    for (size_t i = 0; i < results.size (); i++) {
      Accumulator acc;
      project (cp, results[i], acc);

      if (count (acc) > 0) {
        MESSAGE_ERR ("----------------------------------------------------------");
        MESSAGE_ERR (results[i].before.transpose ());
        MESSAGE_ERR ("Error rate: " << count (acc) << " / " << 10);
        MESSAGE_ERR ("----------------------------------------------------------");
        status = EXIT_FAILURE;
      }
    }
    return status;
  }

  namespace hrp2 {
    using namespace hpp_test;
    int launch () {
      /// Create the robot
      DevicePtr_t robot = Device::create ("hrp2");
      hpp_test::robot = robot;
      loadHRP2 (robot);
      loadHRP2constraints (false);

      return process ();
    }
  }

  namespace pr2 {
    using namespace hpp_test;
    int launch () {
      /// Create the robot
      DevicePtr_t robot = Device::create ("PR2");
      hpp_test::robot = robot;
      loadPR2 (robot);
      loadPR2constraints (false);

      return process ();
    }
  }
}

int launcher (int (*f) ()) {
  Timer t (true);
  int ret = f ();
  t.stop ();
  MESSAGE_INF ("Time: " << t.duration ());
  return ret;
}

int main () {
  bool success = true;
  //success = (EXIT_SUCCESS == launcher (projection::hrp2::launch)) && success;
  //success = (EXIT_SUCCESS == launcher (svd::hrp2::launch       )) && success;
  //success = (EXIT_SUCCESS == launcher (svd::pr2::launch        )) && success;
  //success = (EXIT_SUCCESS == launcher (projection::pr2::launch )) && success;
  success = (EXIT_SUCCESS == launcher (shuffle::hrp2::launch)) && success;
  success = (EXIT_SUCCESS == launcher (shuffle::hrp2::launch       )) && success;
  if (success) return EXIT_SUCCESS;
  return EXIT_FAILURE;
}