rbprmbuilder.impl.cc 79.1 KB
Newer Older
Steve Tonneau's avatar
Steve Tonneau committed
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
// Copyright (c) 2012 CNRS
// Author: Florent Lamiraux, Joseph Mirabel
//
// This file is part of hpp-manipulation-corba.
// hpp-manipulation-corba 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.
//
// hpp-manipulation-corba 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
// hpp-manipulation-corba.  If not, see
// <http://www.gnu.org/licenses/>.

//#include <hpp/fcl/math/transform.h>
#include <hpp/util/debug.hh>
Steve Tonneau's avatar
Steve Tonneau committed
20
#include "hpp/corbaserver/rbprm/rbprmbuilder.hh"
Steve Tonneau's avatar
Steve Tonneau committed
21
22
#include "rbprmbuilder.impl.hh"
#include "hpp/rbprm/rbprm-device.hh"
Steve Tonneau's avatar
Steve Tonneau committed
23
#include "hpp/rbprm/rbprm-validation.hh"
24
#include "hpp/rbprm/interpolation/rbprm-path-interpolation.hh"
Steve Tonneau's avatar
Steve Tonneau committed
25
26
#include "hpp/rbprm/interpolation/limb-rrt.hh"
#include "hpp/rbprm/interpolation/com-rrt.hh"
27
#include "hpp/rbprm/interpolation/spline/effector-rrt.hh"
Steve Tonneau's avatar
Steve Tonneau committed
28
#include "hpp/rbprm/stability/stability.hh"
Steve Tonneau's avatar
Steve Tonneau committed
29
#include "hpp/rbprm/sampling/sample-db.hh"
Steve Tonneau's avatar
Steve Tonneau committed
30
#include "hpp/model/urdf/util.hh"
31
#include "hpp/core/straight-path.hh"
32
#include "hpp/model/joint.hh"
33
34
35
#include "hpp/core/config-validations.hh"
#include "hpp/core/collision-validation-report.hh"
#include <hpp/core/subchain-path.hh>
36
37
#include <hpp/core/basic-configuration-shooter.hh>
#include <hpp/core/collision-validation.hh>
Steve Tonneau's avatar
Steve Tonneau committed
38
#include <fstream>
Steve Tonneau's avatar
Steve Tonneau committed
39

40
41
42
43
#ifdef PROFILE
    #include "hpp/rbprm/rbprm-profiler.hh"
#endif

Steve Tonneau's avatar
Steve Tonneau committed
44
45


Steve Tonneau's avatar
Steve Tonneau committed
46
47
48
49
namespace hpp {
  namespace rbprm {
    namespace impl {

Steve Tonneau's avatar
Steve Tonneau committed
50
51
52
    RbprmBuilder::RbprmBuilder ()
    : POA_hpp::corbaserver::rbprm::RbprmBuilder()
    , romLoaded_(false)
Steve Tonneau's avatar
Steve Tonneau committed
53
    , fullBodyLoaded_(false)
Steve Tonneau's avatar
Steve Tonneau committed
54
    , bindShooter_()
Steve Tonneau's avatar
Steve Tonneau committed
55
    , analysisFactory_(0)
Steve Tonneau's avatar
Steve Tonneau committed
56
57
58
59
    {
        // NOTHING
    }

Steve Tonneau's avatar
Steve Tonneau committed
60
61
62
63
64
65
66
67
68
    void RbprmBuilder::loadRobotRomModel(const char* robotName,
         const char* rootJointType,
         const char* packageName,
         const char* modelName,
         const char* urdfSuffix,
         const char* srdfSuffix) throw (hpp::Error)
    {
        try
        {
Steve Tonneau's avatar
Steve Tonneau committed
69
70
71
            hpp::model::DevicePtr_t romDevice = model::Device::create (robotName);
            romDevices_.insert(std::make_pair(robotName, romDevice));
            hpp::model::urdf::loadRobotModel (romDevice,
Steve Tonneau's avatar
Steve Tonneau 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
                    std::string (rootJointType),
                    std::string (packageName),
                    std::string (modelName),
                    std::string (urdfSuffix),
                    std::string (srdfSuffix));
        }
        catch (const std::exception& exc)
        {
            hppDout (error, exc.what ());
            throw hpp::Error (exc.what ());
        }
        romLoaded_ = true;
    }

    void RbprmBuilder::loadRobotCompleteModel(const char* robotName,
         const char* rootJointType,
         const char* packageName,
         const char* modelName,
         const char* urdfSuffix,
         const char* srdfSuffix) throw (hpp::Error)
    {
        if(!romLoaded_)
        {
            std::string err("Rom must be loaded before loading complete model") ;
Pierre Fernbach's avatar
Pierre Fernbach committed
96
            hppDout (error, err );
Steve Tonneau's avatar
Steve Tonneau committed
97
98
99
100
            throw hpp::Error(err.c_str());
        }
        try
        {
Steve Tonneau's avatar
Steve Tonneau committed
101
            hpp::model::RbPrmDevicePtr_t device = hpp::model::RbPrmDevice::create (robotName, romDevices_);
Steve Tonneau's avatar
Steve Tonneau committed
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
            hpp::model::urdf::loadRobotModel (device,
                    std::string (rootJointType),
                    std::string (packageName),
                    std::string (modelName),
                    std::string (urdfSuffix),
                    std::string (srdfSuffix));
            // Add device to the planner
            problemSolver_->robot (device);
            problemSolver_->robot ()->controlComputation
            (model::Device::JOINT_POSITION);
        }
        catch (const std::exception& exc)
        {
            hppDout (error, exc.what ());
            throw hpp::Error (exc.what ());
        }
    }

Steve Tonneau's avatar
Steve Tonneau committed
120
121
122
123
124
125
126
127
128
129
    void RbprmBuilder::loadFullBodyRobot(const char* robotName,
         const char* rootJointType,
         const char* packageName,
         const char* modelName,
         const char* urdfSuffix,
         const char* srdfSuffix) throw (hpp::Error)
    {
        try
        {
            model::DevicePtr_t device = model::Device::create (robotName);
130
            hpp::model::urdf::loadRobotModel (device,
Steve Tonneau's avatar
Steve Tonneau committed
131
132
133
134
135
136
                    std::string (rootJointType),
                    std::string (packageName),
                    std::string (modelName),
                    std::string (urdfSuffix),
                    std::string (srdfSuffix));
            fullBody_ = rbprm::RbPrmFullBody::create(device);
Steve Tonneau's avatar
Steve Tonneau committed
137
            problemSolver_->pathValidationType ("Discretized",0.05); // reset to avoid conflict with rbprm path
138
            problemSolver_->robot (fullBody_->device_);
Steve Tonneau's avatar
Steve Tonneau committed
139
            problemSolver_->resetProblem();
140
141
            problemSolver_->robot ()->controlComputation
            (model::Device::JOINT_POSITION);
Steve Tonneau's avatar
Steve Tonneau committed
142
143
144
145
146
147
148
        }
        catch (const std::exception& exc)
        {
            hppDout (error, exc.what ());
            throw hpp::Error (exc.what ());
        }
        fullBodyLoaded_ = true;
149
        analysisFactory_ = new sampling::AnalysisFactory(fullBody_);
Steve Tonneau's avatar
Steve Tonneau committed
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
    }

    hpp::floatSeq* RbprmBuilder::getSampleConfig(const char* limb, unsigned short sampleId) throw (hpp::Error)
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        const T_Limb& limbs = fullBody_->GetLimbs();
        T_Limb::const_iterator lit = limbs.find(std::string(limb));
        if(lit == limbs.end())
        {
            std::string err("No limb " + std::string(limb) + "was defined for robot" + fullBody_->device_->name());
            throw Error (err.c_str());
        }
        const RbPrmLimbPtr_t& limbPtr = lit->second;
        hpp::floatSeq *dofArray;
        Eigen::VectorXd config = fullBody_->device_->currentConfiguration ();
        if(sampleId > limbPtr->sampleContainer_.samples_.size())
        {
            std::string err("Limb " + std::string(limb) + "does not have samples.");
            throw Error (err.c_str());
        }
        const sampling::Sample& sample = limbPtr->sampleContainer_.samples_[sampleId];
Steve Tonneau's avatar
Steve Tonneau committed
172
        config.segment(sample.startRank_, sample.length_) = sample.configuration_;
Steve Tonneau's avatar
Steve Tonneau committed
173
174
175
176
177
178
179
        dofArray = new hpp::floatSeq();
        dofArray->length(_CORBA_ULong(config.rows()));
        for(std::size_t i=0; i< _CORBA_ULong(config.rows()); i++)
          (*dofArray)[(_CORBA_ULong)i] = config [i];
        return dofArray;
    }

Steve Tonneau's avatar
Steve Tonneau committed
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

    hpp::floatSeq* RbprmBuilder::getSamplePosition(const char* limb, unsigned short sampleId) throw (hpp::Error)
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        const T_Limb& limbs = fullBody_->GetLimbs();
        T_Limb::const_iterator lit = limbs.find(std::string(limb));
        if(lit == limbs.end())
        {
            std::string err("No limb " + std::string(limb) + "was defined for robot" + fullBody_->device_->name());
            throw Error (err.c_str());
        }
        const RbPrmLimbPtr_t& limbPtr = lit->second;
        hpp::floatSeq *dofArray;
        if(sampleId > limbPtr->sampleContainer_.samples_.size())
        {
            std::string err("Limb " + std::string(limb) + "does not have samples.");
            throw Error (err.c_str());
        }
        const sampling::Sample& sample = limbPtr->sampleContainer_.samples_[sampleId];
        const fcl::Vec3f& position = sample.effectorPosition_;
        dofArray = new hpp::floatSeq();
        dofArray->length(_CORBA_ULong(3));
        for(std::size_t i=0; i< 3; i++)
          (*dofArray)[(_CORBA_ULong)i] = position [i];
        return dofArray;
    }

Steve Tonneau's avatar
Steve Tonneau committed
208

209
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
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
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
    typedef Eigen::Matrix <value_type, 4, 3, Eigen::RowMajor> Matrix43;
    typedef Eigen::Matrix <value_type, 4, 3, Eigen::RowMajor> Rotation;
    typedef Eigen::Ref<Matrix43> Ref_matrix43;

    std::vector<fcl::Vec3f> computeRectangleContact(const rbprm::RbPrmFullBodyPtr_t device,
                                                    const rbprm::State& state)
    {
        std::vector<fcl::Vec3f> res;
        const rbprm::T_Limb& limbs = device->GetLimbs();
        rbprm::RbPrmLimbPtr_t limb;
        Matrix43 p; Eigen::Matrix3d R;
        for(std::map<std::string, fcl::Vec3f>::const_iterator cit = state.contactPositions_.begin();
            cit != state.contactPositions_.end(); ++cit)
        {
            const std::string& name = cit->first;
            const fcl::Vec3f& position = cit->second;
            limb = limbs.at(name);
            const double& lx = limb->x_, ly = limb->y_;
            p << lx,  ly, 0,
                 lx, -ly, 0,
                -lx, -ly, 0,
                -lx,  ly, 0;
            if(limb->contactType_ == _3_DOF)
            {
                //create rotation matrix from normal
                fcl::Vec3f z_fcl = state.contactNormals_.at(name);
                Eigen::Vector3d z,x,y;
                for(int i =0; i<3; ++i) z[i] = z_fcl[i];
                x = z.cross(Eigen::Vector3d(0,-1,0));
                if(x.norm() < 10e-6)
                {
                    y = z.cross(fcl::Vec3f(1,0,0));
                    y.normalize();
                    x = y.cross(z);
                }
                else
                {
                    x.normalize();
                    y = z.cross(x);
                }
                R.block<3,1>(0,0) = x;
                R.block<3,1>(0,1) = y;
                R.block<3,1>(0,2) = z;
            }
            else
            {
                const fcl::Matrix3f& fclRotation = state.contactRotation_.at(name);
                for(int i =0; i< 3; ++i)
                    for(int j =0; j<3;++j)
                        R(i,j) = fclRotation(i,j);
            }
            for(std::size_t i =0; i<4; ++i)
            {
                res.push_back(position + (R*p.row(i).transpose()));
                res.push_back(state.contactNormals_.at(name));
            }
        }
        return res;
    }

    model::Configuration_t dofArrayToConfig (const std::size_t& deviceDim,
      const hpp::floatSeq& dofArray)
    {
        std::size_t configDim = (std::size_t)dofArray.length();
        // Fill dof vector with dof array.
        model::Configuration_t config; config.resize (configDim);
        for (std::size_t iDof = 0; iDof < configDim; iDof++) {
            config [iDof] = (double)dofArray[(_CORBA_ULong)iDof];
        }
        // fill the vector by zero
        hppDout (info, "config dimension: " <<configDim
           <<",  deviceDim "<<deviceDim);
        if(configDim != deviceDim){
            throw hpp::Error ("dofVector Does not match");
        }
        return config;
    }

    model::Configuration_t dofArrayToConfig (const model::DevicePtr_t& robot,
      const hpp::floatSeq& dofArray)
    {
        return dofArrayToConfig(robot->configSize(), dofArray);
    }

    T_Configuration doubleDofArrayToConfig (const std::size_t& deviceDim,
      const hpp::floatSeqSeq& doubleDofArray)
    {
        std::size_t configsDim = (std::size_t)doubleDofArray.length();
        T_Configuration res;
        for (_CORBA_ULong iConfig = 0; iConfig < configsDim; iConfig++)
        {
            res.push_back(dofArrayToConfig(deviceDim, doubleDofArray[iConfig]));
        }
        return res;
    }

    T_Configuration doubleDofArrayToConfig (const model::DevicePtr_t& robot,
      const hpp::floatSeqSeq& doubleDofArray)
    {
        return doubleDofArrayToConfig(robot->configSize(), doubleDofArray);
    }

    hpp::floatSeqSeq* RbprmBuilder::getEffectorPosition(const char* lb, const hpp::floatSeq& configuration) throw (hpp::Error)
    {
        try
        {
            const std::string limbName(lb);
            const RbPrmLimbPtr_t limb = fullBody_->GetLimbs().at(limbName);
            model::Configuration_t config = dofArrayToConfig (fullBody_->device_, configuration);
            fullBody_->device_->currentConfiguration(config);
            fullBody_->device_->computeForwardKinematics();
            State state;
            state.configuration_ = config;
            state.contacts_[limbName] = true;
            const fcl::Vec3f z = limb->effector_->currentTransformation().getRotation() * limb->normal_;
            const fcl::Vec3f position = limb->effector_->currentTransformation().getTranslation();
            const fcl::Matrix3f alignRotation = tools::GetRotationMatrix(z,fcl::Vec3f(0,0,1));
            fcl::Matrix3f rotation = alignRotation * limb->effector_->initialPosition ().getRotation();
            fcl::Vec3f posOffset = position + rotation * limb->offset_;
            state.contactPositions_[limbName] = posOffset;
            state.contactNormals_[limbName] = fcl::Vec3f(0,0,1);
            state.contactRotation_[limbName] = limb->effector_->currentTransformation().getRotation();
            std::vector<fcl::Vec3f> poss = (computeRectangleContact(fullBody_, state));

            hpp::floatSeqSeq *res;
            res = new hpp::floatSeqSeq ();
            res->length ((_CORBA_ULong)poss.size ());
            for(std::size_t i = 0; i < poss.size(); ++i)
            {
                _CORBA_ULong size = (_CORBA_ULong) (3);
                double* dofArray = hpp::floatSeq::allocbuf(size);
                hpp::floatSeq floats (size, size, dofArray, true);
                //convert the config in dofseq
                for(std::size_t j=0; j<3; j++)
                {
                    dofArray[j] = poss[i][j];
                }
                (*res) [(_CORBA_ULong)i] = floats;
            }
            return res;
        }
        catch (const std::exception& exc)
        {
            throw hpp::Error (exc.what ());
        }
    }


Steve Tonneau's avatar
Steve Tonneau committed
357
358
359
360
361
362
363
364
365
    CORBA::UShort RbprmBuilder::getNumSamples(const char* limb) throw (hpp::Error)
    {
        const T_Limb& limbs = fullBody_->GetLimbs();
        T_Limb::const_iterator lit = limbs.find(std::string(limb));
        if(lit == limbs.end())
        {
            std::string err("No limb " + std::string(limb) + "was defined for robot" + fullBody_->device_->name());
            throw Error (err.c_str());
        }
366
        return (CORBA::UShort)(lit->second->sampleContainer_.samples_.size());
Steve Tonneau's avatar
Steve Tonneau committed
367
368
    }

369
370
371
372
373
374
375
376
377
378
379
    floatSeq *RbprmBuilder::getOctreeNodeIds(const char* limb) throw (hpp::Error)
    {
        const T_Limb& limbs = fullBody_->GetLimbs();
        T_Limb::const_iterator lit = limbs.find(std::string(limb));
        if(lit == limbs.end())
        {
            std::string err("No limb " + std::string(limb) + "was defined for robot" + fullBody_->device_->name());
            throw Error (err.c_str());
        }
        const sampling::T_VoxelSampleId& ids =  lit->second->sampleContainer_.samplesInVoxels_;
        hpp::floatSeq* dofArray = new hpp::floatSeq();
380
        dofArray->length((_CORBA_ULong)ids.size());
381
382
383
        sampling::T_VoxelSampleId::const_iterator it = ids.begin();
        for(std::size_t i=0; i< _CORBA_ULong(ids.size()); ++i, ++it)
        {
384
          (*dofArray)[(_CORBA_ULong)i] = (double)it->first;
385
386
387
388
        }
        return dofArray;
    }

Steve Tonneau's avatar
Steve Tonneau committed
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
    double RbprmBuilder::getSampleValue(const char* limb, const char* valueName, unsigned short sampleId) throw (hpp::Error)
    {
        const T_Limb& limbs = fullBody_->GetLimbs();
        T_Limb::const_iterator lit = limbs.find(std::string(limb));
        if(lit == limbs.end())
        {
            std::string err("No limb " + std::string(limb) + "was defined for robot" + fullBody_->device_->name());
            throw Error (err.c_str());
        }
        const sampling::SampleDB& database = lit->second->sampleContainer_;
        if (database.samples_.size() <= sampleId)
        {
            std::string err("unexisting sample id " + sampleId);
            throw Error (err.c_str());
        }
        sampling::T_Values::const_iterator cit = database.values_.find(std::string(valueName));
        if(cit == database.values_.end())
        {
            std::string err("value not existing in database " + std::string(valueName));
            throw Error (err.c_str());
        }
        return cit->second[sampleId];
    }

413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430

    double RbprmBuilder::getEffectorDistance(unsigned short state1, unsigned short state2) throw (hpp::Error)
    {
        try
        {
            std::size_t s1((std::size_t)state1), s2((std::size_t)state2);
            if(lastStatesComputed_.size () < s1 || lastStatesComputed_.size () < s2 )
            {
                throw std::runtime_error ("did not find a states at indicated indices: " + std::string(""+s1) + ", " + std::string(""+s2));
            }
            return rbprm::effectorDistance(lastStatesComputed_[s1], lastStatesComputed_[s2]);
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

Steve Tonneau's avatar
Steve Tonneau committed
431
432
433
434
    std::vector<std::string> stringConversion(const hpp::Names_t& dofArray)
    {
        std::vector<std::string> res;
        std::size_t dim = (std::size_t)dofArray.length();
435
        for (_CORBA_ULong iDof = 0; iDof < dim; iDof++)
Steve Tonneau's avatar
Steve Tonneau committed
436
437
438
439
440
        {
            res.push_back(std::string(dofArray[iDof]));
        }
        return res;
    }
Steve Tonneau's avatar
Steve Tonneau committed
441

Steve Tonneau's avatar
Steve Tonneau committed
442
443
444
445
    std::vector<double> doubleConversion(const hpp::floatSeq& dofArray)
    {
        std::vector<double> res;
        std::size_t dim = (std::size_t)dofArray.length();
446
        for (_CORBA_ULong iDof = 0; iDof < dim; iDof++)
Steve Tonneau's avatar
Steve Tonneau committed
447
448
449
450
451
452
        {
            res.push_back(dofArray[iDof]);
        }
        return res;
    }

Steve Tonneau's avatar
Steve Tonneau committed
453
454
455
456
457
458

    void RbprmBuilder::setFilter(const hpp::Names_t& roms) throw (hpp::Error)
    {
        bindShooter_.romFilter_ = stringConversion(roms);
    }

459

460
    void RbprmBuilder::setAffordanceFilter(const char* romName, const hpp::Names_t& affordances) throw (hpp::Error)
461
    {
462
463
464
465
        std::string name (romName);
				std::vector<std::string> affNames = stringConversion(affordances);
        bindShooter_.affFilter_.erase(name);
        bindShooter_.affFilter_.insert(std::make_pair(name,affNames));
466
467
    }

Steve Tonneau's avatar
Steve Tonneau committed
468
469
470
471
472
473
474
475
476
477
478
    void RbprmBuilder::boundSO3(const hpp::floatSeq& limitszyx) throw (hpp::Error)
    {
        std::vector<double> limits = doubleConversion(limitszyx);
        if(limits.size() !=6)
        {
            throw Error ("Can not bound SO3, array of 6 double required");
        }
        bindShooter_.so3Bounds_ = limits;

    }

479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
    double RbprmBuilder::projectStateToCOM(unsigned short stateId, const hpp::floatSeq& com) throw (hpp::Error)
    {
        try
        {
            if(lastStatesComputed_.size() <= stateId)
            {
                throw std::runtime_error ("Unexisting state " + std::string(""+(stateId)));
            }
            model::Configuration_t com_target = dofArrayToConfig (3, com);
            State& s = lastStatesComputed_[stateId];
            bool succes (false);
            hpp::model::Configuration_t c = rbprm::interpolation::projectOnCom(fullBody_, problemSolver_->problem(),s,com_target,succes);
            if(succes)
            {
                std::cout << "updating config " << lastStatesComputed_[stateId].configuration_ << std::endl;
                lastStatesComputed_[stateId].configuration_ = c;
                std::cout << "updated config " << lastStatesComputed_[stateId].configuration_ << std::endl;
                lastStatesComputedTime_[stateId].second.configuration_ = c;
                return 1.;
            }
            return 0;
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

507
508
    hpp::floatSeq* RbprmBuilder::generateContacts(const hpp::floatSeq& configuration,
			const hpp::floatSeq& direction) throw (hpp::Error)
Steve Tonneau's avatar
Steve Tonneau committed
509
510
511
512
513
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        try
        {
514
            fcl::Vec3f dir;
Steve Tonneau's avatar
Steve Tonneau committed
515
516
            for(std::size_t i =0; i <3; ++i)
            {
517
                dir[i] = direction[(_CORBA_ULong)i];
Steve Tonneau's avatar
Steve Tonneau committed
518
            }
519
520
521
						const affMap_t &affMap = problemSolver_->map
							<std::vector<boost::shared_ptr<model::CollisionObject> > > ();
		        if (affMap.empty ()) {
522
523
    	        throw hpp::Error ("No affordances found. Unable to generate Contacts.");
      		  }
Steve Tonneau's avatar
Steve Tonneau committed
524
            model::Configuration_t config = dofArrayToConfig (fullBody_->device_, configuration);
525
526
            rbprm::State state = rbprm::ComputeContacts(fullBody_,config,
							affMap, bindShooter_.affFilter_, dir);
Steve Tonneau's avatar
Steve Tonneau committed
527
            hpp::floatSeq* dofArray = new hpp::floatSeq();
Steve Tonneau's avatar
stair    
Steve Tonneau committed
528
            dofArray->length(_CORBA_ULong(state.configuration_.rows()));
Steve Tonneau's avatar
Steve Tonneau committed
529
530
531
532
533
534
535
536
            for(std::size_t i=0; i< _CORBA_ULong(config.rows()); i++)
              (*dofArray)[(_CORBA_ULong)i] = state.configuration_ [i];
            return dofArray;
        } catch (const std::exception& exc) {
        throw hpp::Error (exc.what ());
        }
    }

537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
    hpp::floatSeq* RbprmBuilder::generateGroundContact(const hpp::Names_t& contactLimbs) throw (hpp::Error)
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        try
        {
            fcl::Vec3f z(0,0,1);
            ValidationReportPtr_t report = ValidationReportPtr_t(new CollisionValidationReport);
            core::BasicConfigurationShooterPtr_t  shooter = core::BasicConfigurationShooter::create(fullBody_->device_);
            for(int i =0; i< 1000; ++i)
            {
                std::vector<std::string> names = stringConversion(contactLimbs);
                core::ConfigProjectorPtr_t proj = core::ConfigProjector::create(fullBody_->device_,"proj", 1e-4, 1000);
                //hpp::tools::LockJointRec(limb->limb_->name(), body->device_->rootJoint(), proj);
                for(std::vector<std::string>::const_iterator cit = names.begin(); cit !=names.end(); ++cit)
                {
                    rbprm::RbPrmLimbPtr_t limb = fullBody_->GetLimbs().at(*cit);
                    fcl::Transform3f localFrame, globalFrame;
555
                    localFrame.setTranslation(-limb->offset_);
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
                    std::vector<bool> posConstraints;
                    std::vector<bool> rotConstraints;
                    posConstraints.push_back(false);posConstraints.push_back(false);posConstraints.push_back(true);
                    rotConstraints.push_back(true);rotConstraints.push_back(true);rotConstraints.push_back(true);
                    proj->add(core::NumericalConstraint::create (constraints::Position::create("",fullBody_->device_,
                                                                                               limb->effector_,
                                                                                               globalFrame,
                                                                                               localFrame,
                                                                                               posConstraints)));
                    if(limb->contactType_ == hpp::rbprm::_6_DOF)
                    {
                        // rotation matrix around z
                        value_type theta = 2*(value_type(rand()) / value_type(RAND_MAX) - 0.5) * M_PI;
                        fcl::Matrix3f r = tools::GetZRotMatrix(theta);
                        fcl::Matrix3f rotation = r * limb->effector_->initialPosition ().getRotation();
                        proj->add(core::NumericalConstraint::create (constraints::Orientation::create("",fullBody_->device_,
                                                                                                      limb->effector_,
                                                                                                      fcl::Transform3f(rotation),
                                                                                                      rotConstraints)));
                    }
                }
                ConfigurationPtr_t configptr = shooter->shoot();
                Configuration_t config = *configptr;
                if(proj->apply(config) && config[2]> 0.3)
                {
                    if(problemSolver_->problem()->configValidations()->validate(config,report))
                    {
                        State tmp;
                        for(std::vector<std::string>::const_iterator cit = names.begin(); cit !=names.end(); ++cit)
                        {
                            std::string limbId = *cit;
                            rbprm::RbPrmLimbPtr_t limb = fullBody_->GetLimbs().at(*cit);
                            tmp.contacts_[limbId] = true;
                            tmp.contactPositions_[limbId] = limb->effector_->currentTransformation().getTranslation();
                            tmp.contactRotation_[limbId] = limb->effector_->currentTransformation().getRotation();
                            tmp.contactNormals_[limbId] = z;
                            tmp.configuration_ = config;
                            ++tmp.nbContacts;
                        }
                        if(stability::IsStable(fullBody_,tmp)>=0)
                        {
                            config[0]=0;
                            config[1]=0;
                            hpp::floatSeq* dofArray = new hpp::floatSeq();
                            dofArray->length(_CORBA_ULong(config.rows()));
                            for(std::size_t j=0; j< config.rows(); j++)
                            {
                              (*dofArray)[(_CORBA_ULong)j] = config [j];
                            }
                            return dofArray;
                        }
                    }
                }
            }
            throw (std::runtime_error("could not generate contact configuration after 1000 trials"));
        } catch (const std::exception& exc) {
        throw hpp::Error (exc.what ());
        }
    }

616
617
618
619
620
621
622
623
    hpp::floatSeq* RbprmBuilder::getContactSamplesIds(const char* limbname,
                                        const hpp::floatSeq& configuration,
                                        const hpp::floatSeq& direction) throw (hpp::Error)
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        try
        {
624
            fcl::Vec3f dir;
625
626
            for(std::size_t i =0; i <3; ++i)
            {
627
                dir[i] = direction[(_CORBA_ULong)i];
628
629
            }
            model::Configuration_t config = dofArrayToConfig (fullBody_->device_, configuration);
Steve Tonneau's avatar
Steve Tonneau committed
630
631
            model::Configuration_t save = fullBody_->device_->currentConfiguration();
            fullBody_->device_->currentConfiguration(config);
632
633
634
635
636
637

            sampling::T_OctreeReport finalSet;
            rbprm::T_Limb::const_iterator lit = fullBody_->GetLimbs().find(std::string(limbname));
            if(lit == fullBody_->GetLimbs().end())
            {
                throw std::runtime_error ("Impossible to find limb for joint "
Steve Tonneau's avatar
Steve Tonneau committed
638
                                          + std::string(limbname) + " to robot; limb not defined.");
639
640
            }
            const RbPrmLimbPtr_t& limb = lit->second;
Steve Tonneau's avatar
Steve Tonneau committed
641
            fcl::Transform3f transform = limb->limb_->robot()->rootJoint()->childJoint(0)->currentTransformation (); // get root transform from configuration
642
                        // TODO fix as in rbprm-fullbody.cc!!
643
644
645
646
647
648
            std::vector<sampling::T_OctreeReport> reports(problemSolver_->collisionObstacles().size());
            std::size_t i (0);
            //#pragma omp parallel for
            for(model::ObjectVector_t::const_iterator oit = problemSolver_->collisionObstacles().begin();
                oit != problemSolver_->collisionObstacles().end(); ++oit, ++i)
            {
Steve Tonneau's avatar
Steve Tonneau committed
649
                sampling::GetCandidates(limb->sampleContainer_, transform, *oit, dir, reports[i]);
650
651
652
653
654
655
656
            }
            for(std::vector<sampling::T_OctreeReport>::const_iterator cit = reports.begin();
                cit != reports.end(); ++cit)
            {
                finalSet.insert(cit->begin(), cit->end());
            }
            hpp::floatSeq* dofArray = new hpp::floatSeq();
657
            dofArray->length((_CORBA_ULong)finalSet.size());
658
659
660
            sampling::T_OctreeReport::const_iterator candCit = finalSet.begin();
            for(std::size_t i=0; i< _CORBA_ULong(finalSet.size()); ++i, ++candCit)
            {
661
              (*dofArray)[(_CORBA_ULong)i] = (double)candCit->sample_->id_;
662
            }
Steve Tonneau's avatar
Steve Tonneau committed
663
            fullBody_->device_->currentConfiguration(save);
664
665
666
667
668
669
            return dofArray;
        } catch (const std::exception& exc) {
        throw hpp::Error (exc.what ());
        }
    }

670
671
672
673
674
675
676
    hpp::floatSeq* RbprmBuilder::getSamplesIdsInOctreeNode(const char* limb,
                                                           double octreeNodeId) throw (hpp::Error)
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        try
        {
677
            long ocId ((long)octreeNodeId);
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
            const T_Limb& limbs = fullBody_->GetLimbs();
            T_Limb::const_iterator lit = limbs.find(std::string(limb));
            if(lit == limbs.end())
            {
                std::string err("No limb " + std::string(limb) + "was defined for robot" + fullBody_->device_->name());
                throw Error (err.c_str());
            }
            const sampling::T_VoxelSampleId& sampleIds =  lit->second->sampleContainer_.samplesInVoxels_;
            sampling::T_VoxelSampleId::const_iterator cit = sampleIds.find(ocId);
            if(cit == sampleIds.end())
            {
                std::stringstream ss; ss << ocId;
                std::string err("No octree node with id " + ss.str() + "was defined for robot" + fullBody_->device_->name());
                throw Error (err.c_str());
            }
            const sampling::VoxelSampleId& ids = cit->second;
            hpp::floatSeq* dofArray = new hpp::floatSeq();
695
            dofArray->length((_CORBA_ULong)ids.second);
696
697
698
            std::size_t sampleId = ids.first;
            for(std::size_t i=0; i< _CORBA_ULong(ids.second); ++i, ++sampleId)
            {
699
              (*dofArray)[(_CORBA_ULong)i] = (double)sampleId;
700
701
702
703
704
705
706
            }
            return dofArray;
        } catch (const std::exception& exc) {
        throw hpp::Error (exc.what ());
        }
    }

707
    void RbprmBuilder::addLimb(const char* id, const char* limb, const char* effector, const hpp::floatSeq& offset, const hpp::floatSeq& normal, double x, double y,
708
                               unsigned short samples, const char* heuristicName, double resolution, const char *contactType, double disableEffectorCollision) throw (hpp::Error)
Steve Tonneau's avatar
Steve Tonneau committed
709
710
711
712
713
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        try
        {
Steve Tonneau's avatar
Steve Tonneau committed
714
            fcl::Vec3f off, norm;
715
716
            for(std::size_t i =0; i <3; ++i)
            {
717
718
                off[i] = offset[(_CORBA_ULong)i];
                norm[i] = normal[(_CORBA_ULong)i];
719
            }
720
721
722
723
724
            ContactType cType = hpp::rbprm::_6_DOF;
            if(std::string(contactType) == "_3_DOF")
            {
                cType = hpp::rbprm::_3_DOF;
            }
725
726
            fullBody_->AddLimb(std::string(id), std::string(limb), std::string(effector), off, norm, x, y,
                               problemSolver_->collisionObstacles(), samples,heuristicName,resolution,cType,disableEffectorCollision > 0.5);
Steve Tonneau's avatar
Steve Tonneau committed
727
728
729
730
731
732
733
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

Steve Tonneau's avatar
Steve Tonneau committed
734

735
    void RbprmBuilder::addLimbDatabase(const char* databasePath, const char* id, const char* heuristicName, double loadValues, double disableEffectorCollision) throw (hpp::Error)
Steve Tonneau's avatar
Steve Tonneau committed
736
737
738
739
740
741
    {
        if(!fullBodyLoaded_)
            throw Error ("No full body robot was loaded");
        try
        {
            std::string fileName(databasePath);
742
743
            fullBody_->AddLimb(fileName, std::string(id), problemSolver_->collisionObstacles(), heuristicName, loadValues > 0.5,
                               disableEffectorCollision > 0.5);
Steve Tonneau's avatar
Steve Tonneau committed
744
745
746
747
748
749
750
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

751
752
753
    void SetPositionAndNormal(rbprm::State& state,
			hpp::rbprm::RbPrmFullBodyPtr_t fullBody, const hpp::floatSeq& configuration,
			const hpp::Names_t& contactLimbs)
Steve Tonneau's avatar
Steve Tonneau committed
754
755
756
757
    {
        core::Configuration_t old = fullBody->device_->currentConfiguration();
        model::Configuration_t config = dofArrayToConfig (fullBody->device_, configuration);
        fullBody->device_->currentConfiguration(config);
Steve Tonneau's avatar
Steve Tonneau committed
758
        fullBody->device_->computeForwardKinematics();
Steve Tonneau's avatar
Steve Tonneau committed
759
760
761
762
763
764
765
        std::vector<std::string> names = stringConversion(contactLimbs);
        for(std::vector<std::string>::const_iterator cit = names.begin(); cit != names.end();++cit)
        {
            rbprm::T_Limb::const_iterator lit = fullBody->GetLimbs().find(*cit);
            if(lit == fullBody->GetLimbs().end())
            {
                throw std::runtime_error ("Impossible to find limb for joint "
Steve Tonneau's avatar
Steve Tonneau committed
766
                                          + (*cit) + " to robot; limb not defined");
Steve Tonneau's avatar
Steve Tonneau committed
767
768
769
770
771
            }
            const core::JointPtr_t joint = fullBody->device_->getJointByName(lit->second->effector_->name());
            const fcl::Transform3f& transform =  joint->currentTransformation ();
            const fcl::Matrix3f& rot = transform.getRotation();
            state.contactPositions_[*cit] = transform.getTranslation();
Steve Tonneau's avatar
Steve Tonneau committed
772
            state.contactRotation_[*cit] = rot;
Steve Tonneau's avatar
Steve Tonneau committed
773
774
            state.contactNormals_[*cit] = fcl::Vec3f(rot(0,2),rot(1,2), rot(2,2));
            state.contacts_[*cit] = true;
Steve Tonneau's avatar
Steve Tonneau committed
775
            state.contactOrder_.push(*cit);
Steve Tonneau's avatar
Steve Tonneau committed
776
777
        }        
        state.nbContacts = state.contactNormals_.size() ;
Steve Tonneau's avatar
Steve Tonneau committed
778
        state.configuration_ = config;
779
780
        state.robustness =  stability::IsStable(fullBody,state);
        state.stable = state.robustness >= 0;
Steve Tonneau's avatar
Steve Tonneau committed
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
        fullBody->device_->currentConfiguration(old);
    }

    void RbprmBuilder::setStartState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error)
    {
        try
        {
            SetPositionAndNormal(startState_,fullBody_, configuration, contactLimbs);
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

    void RbprmBuilder::setEndState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error)
    {
        try
        {
            SetPositionAndNormal(endState_,fullBody_, configuration, contactLimbs);
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

808
809
810
811
812
813
814
815
816
817
    std::vector<State> TimeStatesToStates(const T_StateFrame& ref)
    {
        std::vector<State> res;
        for(CIT_StateFrame cit = ref.begin(); cit != ref.end(); ++cit)
        {
            res.push_back(cit->second);
        }
        return res;
    }

818
    floatSeqSeq* RbprmBuilder::interpolateConfigs(const hpp::floatSeqSeq& configs, double robustnessTreshold, unsigned short filterStates) throw (hpp::Error)
Steve Tonneau's avatar
Steve Tonneau committed
819
820
821
822
823
824
825
826
827
828
829
    {
        try
        {
            if(startState_.configuration_.rows() == 0)
            {
                throw std::runtime_error ("Start state not initialized, can not interpolate ");
            }
            if(endState_.configuration_.rows() == 0)
            {
                throw std::runtime_error ("End state not initialized, can not interpolate ");
            }
830
            T_Configuration configurations = doubleDofArrayToConfig(fullBody_->device_, configs);
831
832
833
834
835
836
837
            const affMap_t &affMap = problemSolver_->map
                        <std::vector<boost::shared_ptr<model::CollisionObject> > > ();
            if (affMap.empty ())
            {
                throw hpp::Error ("No affordances found. Unable to interpolate.");
            }
            hpp::rbprm::interpolation::RbPrmInterpolationPtr_t interpolator = rbprm::interpolation::RbPrmInterpolation::create(fullBody_,startState_,endState_);
838
            lastStatesComputedTime_ = interpolator->Interpolate(affMap, bindShooter_.affFilter_,configurations,robustnessTreshold, filterStates != 0);
839
            lastStatesComputed_ = TimeStatesToStates(lastStatesComputedTime_);
Steve Tonneau's avatar
Steve Tonneau committed
840
841
842
            hpp::floatSeqSeq *res;
            res = new hpp::floatSeqSeq ();

843
            res->length ((_CORBA_ULong)lastStatesComputed_.size ());
Steve Tonneau's avatar
Steve Tonneau committed
844
845
            std::size_t i=0;
            std::size_t id = 0;
846
            for(std::vector<State>::const_iterator cit = lastStatesComputed_.begin(); cit != lastStatesComputed_.end(); ++cit, ++id)
Steve Tonneau's avatar
Steve Tonneau committed
847
848
849
850
851
852
853
854
855
856
857
            {
                std::cout << "ID " << id;
                cit->print();
                const core::Configuration_t config = cit->configuration_;
                _CORBA_ULong size = (_CORBA_ULong) config.size ();
                double* dofArray = hpp::floatSeq::allocbuf(size);
                hpp::floatSeq floats (size, size, dofArray, true);
                //convert the config in dofseq
                for (model::size_type j=0 ; j < config.size() ; ++j) {
                  dofArray[j] = config [j];
                }
858
                (*res) [(_CORBA_ULong)i] = floats;
Steve Tonneau's avatar
Steve Tonneau committed
859
860
861
862
863
864
865
866
867
                ++i;
            }
            return res;
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }
Steve Tonneau's avatar
Steve Tonneau committed
868

869
    hpp::floatSeqSeq* contactCone(RbPrmFullBodyPtr_t& fullBody, State& state, const double friction)
870
871
872
873
    {
        hpp::floatSeqSeq *res;
        res = new hpp::floatSeqSeq ();

874
        std::pair<stability::MatrixXX, stability::VectorX> cone = stability::ComputeCentroidalCone(fullBody, state, friction);
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
        res->length ((_CORBA_ULong)cone.first.rows());
        _CORBA_ULong size = (_CORBA_ULong) cone.first.cols()+1;
        for(int i=0; i < cone.first.rows(); ++i)
        {
            double* dofArray = hpp::floatSeq::allocbuf(size);
            hpp::floatSeq floats (size, size, dofArray, true);
            //convert the row in dofseq
            for (int j=0 ; j < cone.first.cols() ; ++j)
            {
                dofArray[j] = cone.first(i,j);
            }
            dofArray[size-1] =cone.second[i];
            (*res) [(_CORBA_ULong)i] = floats;
        }
        return res;
    }

892
    hpp::floatSeqSeq* RbprmBuilder::getContactCone(unsigned short stateId, double friction) throw (hpp::Error)
893
894
895
896
897
898
899
    {
        try
        {
            if(lastStatesComputed_.size() <= stateId)
            {
                throw std::runtime_error ("Unexisting state " + std::string(""+(stateId)));
            }
900
            return contactCone(fullBody_, lastStatesComputed_[stateId],friction);
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

    State intermediary(const State& firstState, const State& thirdState, unsigned short& cId, bool& success)
    {
        success = false;
        std::vector<std::string> breaks;
        thirdState.contactBreaks(firstState, breaks);
        if(breaks.size() > 1)
        {
            throw std::runtime_error ("too many contact breaks between states" + std::string(""+cId) +
                                      "and " + std::string(""+(cId + 1)));
        }
        if(breaks.size() == 1)
        {
            State intermediary(firstState);
            intermediary.RemoveContact(*breaks.begin());
            success = true;
923
            return intermediary;
924
925
926
927
        }
        return firstState;
    }

928
    hpp::floatSeqSeq* RbprmBuilder::getContactIntermediateCone(unsigned short stateId, double friction) throw (hpp::Error)
929
930
931
932
933
934
935
936
937
938
939
940
941
    {
        try
        {
            if(lastStatesComputed_.size() <= stateId+1)
            {
                throw std::runtime_error ("Unexisting state " + std::string(""+(stateId+1)));
            }
            bool success;
            State intermediaryState = intermediary(lastStatesComputed_[stateId], lastStatesComputed_[stateId+1],stateId,success);
            if(!success)
            {
                throw std::runtime_error ("No contact breaks, hence no intermediate state from state " + std::string(""+(stateId)));
            }
942
            return contactCone(fullBody_,intermediaryState, friction);
943
944
945
946
947
948
949
950
951
952
953
954
        }
        catch(std::runtime_error& e)
        {
            throw Error(e.what());
        }
    }

    core::PathPtr_t makePath(DevicePtr_t device,
                             const ProblemPtr_t& problem,
                             model::ConfigurationIn_t q1,
                             model::ConfigurationIn_t q2)
    {
Steve Tonneau's avatar
Steve Tonneau committed
955
956
        // TODO DT
        return StraightPath::create(device, q1, q2, 0.1);
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
    }

    model::Configuration_t addRotation(CIT_Configuration& pit, const model::value_type& u,
                              model::ConfigurationIn_t q1, model::ConfigurationIn_t q2,
                              model::ConfigurationIn_t ref)
    {
        model::Configuration_t res = ref;
        res.head(3) = *pit;
        res.segment<4>(3) = tools::interpolate(q1, q2, u);
        return res;
    }

    core::PathVectorPtr_t addRotations(const T_Configuration& positions,
                                       model::ConfigurationIn_t q1, model::ConfigurationIn_t q2,
                                       model::ConfigurationIn_t ref, DevicePtr_t device,
                                       const ProblemPtr_t& problem)
    {
        core::PathVectorPtr_t res = core::PathVector::create(device->configSize(), device->numberDof());
        model::value_type size_step = 1 /(model::value_type)(positions.size());
        model::value_type u = 0.;
        CIT_Configuration pit = positions.begin();
        model::Configuration_t previous = addRotation(pit, 0., q1, q2, ref), current;
        ++pit;
        for(;pit != positions.end()-1; ++pit, u+=size_step)
        {
            current = addRotation(pit, u, q1, q2, ref);
            res->appendPath(makePath(device,problem, previous, current));
            previous = current;
        }
        // last configuration is exactly q2
        current = addRotation(pit, 1., q1, q2, ref);
        res->appendPath(makePath(device,problem, previous, current));
        return res;
    }

Steve Tonneau's avatar
Steve Tonneau committed
992
993
994
995
996
997
   core::PathVectorPtr_t generateComPath(RbPrmFullBodyPtr_t& fullBody, core::ProblemSolverPtr_t problemSolver, const hpp::floatSeqSeq& rootPositions,
                          const model::Configuration_t q1, const model::Configuration_t q2) throw (hpp::Error)
    {
        try
        {
            T_Configuration positions = doubleDofArrayToConfig(3, rootPositions);
998
999
1000
            if(positions.size() <2)
            {
                throw std::runtime_error("generateComPath requires at least 2 configurations to generate path");