GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: src/sampling/analysis.cc Lines: 0 203 0.0 %
Date: 2024-02-02 12:21:48 Branches: 0 436 0.0 %

Line Branch Exec Source
1
// Copyright (c) 2014, LAAS-CNRS
2
// Authors: Steve Tonneau (steve.tonneau@laas.fr)
3
//
4
// This file is part of hpp-rbprm.
5
// hpp-rbprm is free software: you can redistribute it
6
// and/or modify it under the terms of the GNU Lesser General Public
7
// License as published by the Free Software Foundation, either version
8
// 3 of the License, or (at your option) any later version.
9
//
10
// hpp-rbprm is distributed in the hope that it will be
11
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
12
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
13
// General Lesser Public License for more details.  You should have
14
// received a copy of the GNU Lesser General Public License along with
15
// hpp-rbprm. If not, see <http://www.gnu.org/licenses/>.
16
17
#include <time.h>
18
19
#include <Eigen/Eigen>
20
#include <Eigen/SVD>
21
#include <boost/bind.hpp>
22
#include <hpp/core/configuration-shooter/uniform.hh>
23
#include <hpp/pinocchio/configuration.hh>
24
#include <hpp/pinocchio/joint.hh>
25
#include <hpp/rbprm/sampling/analysis.hh>
26
27
using namespace hpp;
28
using namespace hpp::pinocchio;
29
using namespace hpp::rbprm;
30
using namespace hpp::rbprm::sampling;
31
32
namespace {
33
enum JacobianMode {
34
  ALL = 0,         // Jacobian is entirely considered
35
  ROTATION = 1,    // Only rotational jacobian is considered
36
  TRANSLATION = 2  // Only translational jacobian is considered
37
};
38
39
Eigen::JacobiSVD<Eigen::MatrixXd> svd(const sampling::Sample& sample,
40
                                      const JacobianMode mode) {
41
  switch (mode) {
42
    case ALL:
43
      return Eigen::JacobiSVD<Eigen::MatrixXd>(sample.jacobian_);
44
    case TRANSLATION:
45
      return Eigen::JacobiSVD<Eigen::MatrixXd>(
46
          sample.jacobian_.block(0, 0, 3, sample.jacobian_.cols()));
47
    case ROTATION:
48
      return Eigen::JacobiSVD<Eigen::MatrixXd>(
49
          sample.jacobian_.block(3, 0, 3, sample.jacobian_.cols()));
50
    default:
51
      throw std::runtime_error(
52
          "Can not perform SVD on subjacobian, unknown JacobianMode");
53
      break;
54
  }
55
}
56
57
double manipulability(const JacobianMode mode, const SampleDB& /*sampleDB*/,
58
                      const sampling::Sample& sample) {
59
  double det;
60
  Eigen::MatrixXd sub;
61
  switch (mode) {
62
    case ALL:
63
      det = sample.jacobianProduct_.determinant();
64
      break;
65
    case TRANSLATION:
66
      sub = sample.jacobian_.block(0, 0, 3, sample.jacobian_.cols());
67
      det = (sub * sub.transpose()).determinant();
68
      break;
69
    case ROTATION:
70
      sub = sample.jacobian_.block(3, 0, 3, sample.jacobian_.cols());
71
      det = (sub * sub.transpose()).determinant();
72
      break;
73
    default:
74
      throw std::runtime_error(
75
          "Can not compute subjacobian, unknown JacobianMode");
76
      break;
77
  }
78
  return det > 0 ? sqrt(det) : 0;
79
}
80
81
double isotropy(const JacobianMode mode, const SampleDB& /*sampleDB*/,
82
                const sampling::Sample& sample) {
83
  Eigen::JacobiSVD<Eigen::MatrixXd> svdOfJ(svd(sample, mode));
84
  const Eigen::VectorXd S = svdOfJ.singularValues();
85
  double min = std::numeric_limits<double>::max();
86
  double max = 0;
87
  for (int i = 0; i < S.rows(); ++i) {
88
    double v = S[i];
89
    if (v < min) min = v;
90
    if (v > max) max = v;
91
  }
92
  return (max > 0) ? 1 - sqrt(1 - min * min / max * max) : 0;
93
}
94
95
double minSing(const JacobianMode mode, const SampleDB& /*sampleDB*/,
96
               const sampling::Sample& sample) {
97
  Eigen::JacobiSVD<Eigen::MatrixXd> svdOfJ(svd(sample, mode));
98
  const Eigen::VectorXd S = svdOfJ.singularValues();
99
  double min = std::numeric_limits<double>::max();
100
  for (int i = 0; i < S.rows(); ++i) {
101
    double v = S[i];
102
    if (v < min) min = v;
103
  }
104
  return min;
105
}
106
107
double maxSing(const JacobianMode mode, const SampleDB& /*sampleDB*/,
108
               const sampling::Sample& sample) {
109
  Eigen::JacobiSVD<Eigen::MatrixXd> svdOfJ(svd(sample, mode));
110
  const Eigen::VectorXd S = svdOfJ.singularValues();
111
  double max = -std::numeric_limits<double>::max();
112
  for (int i = 0; i < S.rows(); ++i) {
113
    double v = S[i];
114
    if (v > max) max = v;
115
  }
116
  return max;
117
}
118
119
struct FullBodyDB {
120
  std::vector<hpp::pinocchio::Configuration_t> fullBodyConfigs_;
121
  static FullBodyDB* instance_;
122
123
  static FullBodyDB& Instance(hpp::pinocchio::DevicePtr_t device,
124
                              std::size_t nbSamples = 10000) {
125
    if (!instance_) instance_ = new FullBodyDB;
126
    if (instance_->fullBodyConfigs_.size() < nbSamples)
127
      instance_->GenerateFullBodyDB(nbSamples, device);
128
    return *instance_;
129
  }
130
131
  void GenerateFullBodyDB(std::size_t nbSamples,
132
                          hpp::pinocchio::DevicePtr_t device) {
133
    core::configurationShooter::UniformPtr_t shooter =
134
        core::configurationShooter::Uniform::create(device);
135
    hpp::pinocchio::Configuration_t save(device->currentConfiguration());
136
    core::CollisionValidationPtr_t colVal =
137
        core::CollisionValidation::create(device);
138
    std::size_t i = nbSamples - fullBodyConfigs_.size();
139
    hpp::pinocchio::Configuration_t conf;
140
    while (i > 0) {
141
      shooter->shoot(conf);
142
      device->currentConfiguration(conf);
143
      device->computeForwardKinematics();
144
      core::ValidationReportPtr_t colRep(new core::CollisionValidationReport);
145
146
      if (colVal->validate(conf, colRep)) {
147
        fullBodyConfigs_.push_back(conf);
148
        --i;
149
      }
150
    }
151
    device->currentConfiguration(save);
152
    device->computeForwardKinematics();
153
  }
154
};
155
156
FullBodyDB* FullBodyDB::instance_ = new FullBodyDB;
157
158
// computing probability of auto collision given a large number of full body
159
// samples
160
double selfCollisionProbability(rbprm::RbPrmFullBodyPtr_t fullBody,
161
                                const SampleDB& /*sampleDB*/,
162
                                const sampling::Sample& sample) {
163
  hpp::pinocchio::DevicePtr_t device = fullBody->device_;
164
  hpp::pinocchio::Configuration_t save(device->currentConfiguration());
165
  FullBodyDB& fullBodyDB = FullBodyDB::Instance(device);
166
  core::CollisionValidationPtr_t colVal =
167
      core::CollisionValidation::create(device);
168
  std::size_t totalSamples = fullBodyDB.fullBodyConfigs_.size(),
169
              totalNoCollisions = 0;
170
  for (std::vector<hpp::pinocchio::Configuration_t>::const_iterator cit =
171
           fullBodyDB.fullBodyConfigs_.begin();
172
       cit != fullBodyDB.fullBodyConfigs_.end(); ++cit) {
173
    hpp::pinocchio::Configuration_t conf = *cit;
174
    sampling::Load(sample, conf);
175
    device->currentConfiguration(conf);
176
    device->computeForwardKinematics();
177
    core::ValidationReportPtr_t colRep(new core::CollisionValidationReport);
178
179
    if (colVal->validate(conf, colRep)) ++totalNoCollisions;
180
  }
181
  device->currentConfiguration(save);
182
  device->computeForwardKinematics();
183
  return (double)(totalNoCollisions) / (double)(totalSamples);
184
}
185
186
void distanceRec(const ConfigurationIn_t conf, const std::string& lastJoint,
187
                 hpp::pinocchio::JointPtr_t currentJoint,
188
                 double& currentDistance) {
189
  hpp::pinocchio::size_type rk = currentJoint->rankInConfiguration();
190
  if (currentJoint->configSize() > 0 && currentJoint->isBounded(0)) {
191
    hpp::pinocchio::value_type lb = currentJoint->lowerBound(0),
192
                               ub = currentJoint->upperBound(0);
193
    hpp::pinocchio::value_type val = conf[rk];
194
    val = (val - lb) * (ub - val) / ((ub - lb) * (ub - lb));
195
    currentDistance = std::min(currentDistance, val);
196
  }
197
  if (lastJoint == currentJoint->name() ||
198
      currentJoint->numberChildJoints() == 0)
199
    return;
200
  else
201
    return distanceRec(conf, lastJoint, currentJoint->childJoint(0),
202
                       currentDistance);
203
}
204
205
rbprm::RbPrmLimbPtr_t getLimbFromStartRank(size_type startRank,
206
                                           rbprm::RbPrmFullBodyPtr_t fullBody) {
207
  rbprm::T_Limb::const_iterator cit = fullBody->GetLimbs().begin();
208
  for (; cit != fullBody->GetLimbs().end(); ++cit) {
209
    if (cit->second->limb_->rankInConfiguration() == startRank) break;
210
  }
211
  if (cit == fullBody->GetLimbs().end()) {
212
    for (cit = fullBody->GetNonContactingLimbs().begin();
213
         cit != fullBody->GetNonContactingLimbs().end(); ++cit) {
214
      if (cit->second->limb_->rankInConfiguration() == startRank) break;
215
    }
216
    if (cit == fullBody->GetNonContactingLimbs().end()) {
217
      throw std::runtime_error("Impossible to match sample with a limb");
218
    }
219
  }
220
  return cit->second;
221
}
222
223
double distanceToLimits(rbprm::RbPrmFullBodyPtr_t fullBody,
224
                        const SampleDB& /*sampleDB*/,
225
                        const sampling::Sample& sample) {
226
  // find limb name
227
  rbprm::RbPrmLimbPtr_t limb =
228
      getLimbFromStartRank(sample.startRank_, fullBody);
229
  hpp::pinocchio::DevicePtr_t device = fullBody->device_;
230
  hpp::pinocchio::Configuration_t conf(device->currentConfiguration());
231
  double distance = 1;  // std::numeric_limits<double>::max();
232
  sampling::Load(sample, conf);
233
  distanceRec(conf, limb->effector_.name(), limb->limb_, distance);
234
  distance = 1 - exp(-5 * distance);
235
  return distance;
236
}
237
238
/** compute default weight vector : (TODO add an API to set custom weight
239
vector)
240
* FIXME : lot of assumptions are made here, but they are true for the most
241
common robots used
242
* * the robot's limbs only contain revolute joint
243
* * the robot's root is oriented with x forward and z up (ie. the most common
244
direction of deplacement is along x)
245
246
* by looking at the jacobian of each joint we can check around wich axis the
247
joint is.
248
* We set the weight depending on the axis of each joint :
249
* y : used to move forward, low weight
250
* z : use to turn, medium weight
251
* x : only used for less common behaviour like straffing, high weight
252
* prismatic joint ?? high weight
253
 */
254
Configuration_t computeWeightsFromAxis(rbprm::RbPrmLimbPtr_t limb,
255
                                       hpp::pinocchio::DevicePtr_t device) {
256
  Configuration_t weights =
257
      Configuration_t::Zero(limb->effector_.joint()->rankInVelocity() -
258
                            limb->limb_->rankInVelocity() + 1);
259
  size_t i_weight = 0;
260
  for (size_type i = limb->limb_->rankInVelocity();
261
       i <= limb->effector_.joint()->rankInVelocity(); ++i) {
262
    hpp::pinocchio::vector_t jointJacobian = device->getJointAtVelocityRank(i)
263
                                                 ->jacobian()
264
                                                 .block<6, 1>(0, i)
265
                                                 .transpose();
266
    // hppDout(notice,"Jacobian of joint
267
    // "<<device->getJointAtVelocityRank(i)->name()<<" at id = "<<i);
268
    // hppDout(notice,"joint column : \n"<<jointJacobian);
269
    if (fabs(jointJacobian[4]) > 0.5) {  // rot y
270
      weights[i_weight] = 1.;
271
    } else if (fabs(jointJacobian[5]) > 0.5) {  // rot z
272
      weights[i_weight] = 10.;
273
    } else {  // prismatic or rot x
274
      weights[i_weight] = 100.;
275
    }
276
    i_weight++;
277
  }
278
  return weights;
279
}
280
281
/**
282
 * @brief referenceConfiguration
283
 * @param fullBody
284
 * @param sample
285
 * @param weights vector of size 3, value respectively for x,y,z, rotations
286
 * @return
287
 */
288
double referenceConfiguration(rbprm::RbPrmFullBodyPtr_t fullBody,
289
                              const SampleDB& /*sampleDB*/,
290
                              const sampling::Sample& sample) {
291
  // find limb name
292
  rbprm::RbPrmLimbPtr_t limb =
293
      getLimbFromStartRank(sample.startRank_, fullBody);
294
  hpp::pinocchio::DevicePtr_t device = fullBody->device_;
295
  hpp::pinocchio::Configuration_t conf(device->currentConfiguration());
296
  sampling::Load(sample, conf);  // retrieve the configuration of the sample
297
                                 // (only for the concerned limb)
298
  // hppDout(notice,"Reference conf in analysis :
299
  // "<<pinocchio::displayConfig(fullBody->referenceConfig()));
300
  double distance = 0;
301
  Configuration_t diff(device->numberDof());
302
  Configuration_t weights;
303
  if (fullBody->postureWeights().size() == fullBody->device_->numberDof()) {
304
    weights = fullBody->postureWeights().segment(
305
        limb->limb_->rankInVelocity(),
306
        limb->effector_.joint()->rankInVelocity() -
307
            limb->limb_->rankInVelocity() + 1);
308
    // hppDout(notice,"Analysis : posture weight defined in fullbody :
309
    // "<<hpp::pinocchio::displayConfig(weights));
310
  } else {
311
    weights = computeWeightsFromAxis(limb, device);
312
    // hppDout(notice,"Analysis : posture weight not defined in fullbody,
313
    // computed weight :
314
    // "<<hpp::pinocchio::displayConfig(weights));
315
  }
316
  const int nq = device->configSize() - device->extraConfigSpace().dimension();
317
  hpp::pinocchio::difference(device, conf.segment(0, nq),
318
                             fullBody->referenceConfig().segment(0, nq), diff);
319
  // hppDout(notice,"Reference config in analysis :
320
  // "<<pinocchio::displayConfig(fullBody->referenceConfig())); the difference
321
  // vector depend on the index in the velocity vector, not in the configuration
322
  // we only sum for the index of the current limb
323
  // hppDout(notice,"ref config rank: "<<cit->second->limb_->rankInVelocity()<<"
324
  // ;
325
  // "<<cit->second->effector_->rankInVelocity());
326
  for (size_type i = limb->limb_->rankInVelocity();
327
       i <= limb->effector_.joint()->rankInVelocity(); ++i) {
328
    distance +=
329
        (diff[i] * diff[i]) * weights[i - limb->limb_->rankInVelocity()];
330
  }
331
  // This is an heuristic and not a cost, a null distance is the best result
332
  // TODO : replace hardcoded value with the real max
333
  // but it increase computation time, and the values will be normalized after
334
  // anyways .. hppDout(notice,"distance to ref = "<<sqrt(distance));
335
  if (sqrt(distance) >= 100) {
336
    hppDout(error, "WARNING : max distance to config not big enough");
337
  }
338
  return 100 - (sqrt(distance));
339
}
340
341
}  // namespace
342
343
AnalysisFactory::AnalysisFactory(hpp::rbprm::RbPrmFullBodyPtr_t device)
344
    : device_(device) {
345
  evaluate_.insert(std::make_pair(
346
      "manipulability", boost::bind(&manipulability, JacobianMode(0), _1, _2)));
347
  evaluate_.insert(std::make_pair(
348
      "isotropy", boost::bind(&isotropy, JacobianMode(0), _1, _2)));
349
  evaluate_.insert(std::make_pair(
350
      "minimumSingularValue", boost::bind(&minSing, JacobianMode(0), _1, _2)));
351
  evaluate_.insert(std::make_pair(
352
      "maximumSingularValue", boost::bind(&maxSing, JacobianMode(0), _1, _2)));
353
354
  evaluate_.insert(
355
      std::make_pair("manipulabilityRot",
356
                     boost::bind(&manipulability, JacobianMode(1), _1, _2)));
357
  evaluate_.insert(std::make_pair(
358
      "isotropyRot", boost::bind(&isotropy, JacobianMode(1), _1, _2)));
359
  evaluate_.insert(
360
      std::make_pair("minimumSingularValueRot",
361
                     boost::bind(&minSing, JacobianMode(1), _1, _2)));
362
  evaluate_.insert(
363
      std::make_pair("maximumSingularValueRot",
364
                     boost::bind(&maxSing, JacobianMode(1), _1, _2)));
365
366
  evaluate_.insert(
367
      std::make_pair("manipulabilityTr",
368
                     boost::bind(&manipulability, JacobianMode(2), _1, _2)));
369
  evaluate_.insert(std::make_pair(
370
      "isotropyTr", boost::bind(&isotropy, JacobianMode(2), _1, _2)));
371
  evaluate_.insert(
372
      std::make_pair("minimumSingularValueTr",
373
                     boost::bind(&minSing, JacobianMode(2), _1, _2)));
374
  evaluate_.insert(
375
      std::make_pair("maximumSingularValueTr",
376
                     boost::bind(&maxSing, JacobianMode(2), _1, _2)));
377
378
  evaluate_.insert(std::make_pair(
379
      "selfCollisionProbability",
380
      boost::bind(&selfCollisionProbability, boost::ref(device_), _1, _2)));
381
  evaluate_.insert(std::make_pair(
382
      "jointLimitsDistance",
383
      boost::bind(&distanceToLimits, boost::ref(device_), _1, _2)));
384
  evaluate_.insert(std::make_pair(
385
      "ReferenceConfiguration",
386
      boost::bind(&referenceConfiguration, boost::ref(device_), _1, _2)));
387
}
388
389
AnalysisFactory::~AnalysisFactory() {}
390
391
bool AnalysisFactory::AddAnalysis(const std::string& name,
392
                                  const evaluate func) {
393
  if (evaluate_.find(name) != evaluate_.end()) return false;
394
  evaluate_.insert(std::make_pair(name, func));
395
  return true;
396
}