Line |
Branch |
Exec |
Source |
1 |
|
|
// |
2 |
|
|
// Copyright (c) 2017 CNRS |
3 |
|
|
// Authors: Diane Bury |
4 |
|
|
// |
5 |
|
|
|
6 |
|
|
// Redistribution and use in source and binary forms, with or without |
7 |
|
|
// modification, are permitted provided that the following conditions are |
8 |
|
|
// met: |
9 |
|
|
// |
10 |
|
|
// 1. Redistributions of source code must retain the above copyright |
11 |
|
|
// notice, this list of conditions and the following disclaimer. |
12 |
|
|
// |
13 |
|
|
// 2. Redistributions in binary form must reproduce the above copyright |
14 |
|
|
// notice, this list of conditions and the following disclaimer in the |
15 |
|
|
// documentation and/or other materials provided with the distribution. |
16 |
|
|
// |
17 |
|
|
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
18 |
|
|
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
19 |
|
|
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR |
20 |
|
|
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT |
21 |
|
|
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, |
22 |
|
|
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT |
23 |
|
|
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, |
24 |
|
|
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY |
25 |
|
|
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT |
26 |
|
|
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
27 |
|
|
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH |
28 |
|
|
// DAMAGE. |
29 |
|
|
|
30 |
|
|
#include <hpp/core/collision-path-validation-report.hh> |
31 |
|
|
#include <hpp/core/collision-validation.hh> |
32 |
|
|
#include <hpp/core/config-validations.hh> |
33 |
|
|
#include <hpp/core/path-validations.hh> |
34 |
|
|
#include <hpp/core/path.hh> |
35 |
|
|
#include <hpp/pinocchio/device.hh> |
36 |
|
|
|
37 |
|
|
namespace hpp { |
38 |
|
|
namespace core { |
39 |
|
|
|
40 |
|
✗ |
PathValidationsPtr_t PathValidations::create() { |
41 |
|
✗ |
PathValidations* ptr = new PathValidations(); |
42 |
|
✗ |
return PathValidationsPtr_t(ptr); |
43 |
|
|
} |
44 |
|
|
|
45 |
|
✗ |
void PathValidations::addPathValidation( |
46 |
|
|
const PathValidationPtr_t& pathValidation) { |
47 |
|
✗ |
validations_.push_back(pathValidation); |
48 |
|
|
} |
49 |
|
|
|
50 |
|
✗ |
bool PathValidations::validate(const PathPtr_t& path, bool reverse, |
51 |
|
|
PathPtr_t& validPart, |
52 |
|
|
PathValidationReportPtr_t& validationReport) { |
53 |
|
✗ |
PathPtr_t tempPath = path; |
54 |
|
✗ |
PathPtr_t tempValidPart; |
55 |
|
✗ |
PathValidationReportPtr_t tempValidationReport; |
56 |
|
|
|
57 |
|
✗ |
bool result = true; |
58 |
|
✗ |
value_type lastValidTime = path->timeRange().second; |
59 |
|
✗ |
value_type t = lastValidTime; |
60 |
|
|
|
61 |
|
✗ |
for (std::vector<PathValidationPtr_t>::iterator it = validations_.begin(); |
62 |
|
✗ |
it != validations_.end(); ++it) { |
63 |
|
✗ |
if ((*it)->validate(tempPath, reverse, tempValidPart, |
64 |
|
✗ |
tempValidationReport) == false) { |
65 |
|
✗ |
t = tempValidationReport->getParameter(); |
66 |
|
✗ |
if (t < lastValidTime) { |
67 |
|
✗ |
lastValidTime = t; |
68 |
|
✗ |
tempPath = tempValidPart; |
69 |
|
|
} |
70 |
|
✗ |
result = false; |
71 |
|
|
} |
72 |
|
|
} |
73 |
|
✗ |
validPart = tempPath; |
74 |
|
✗ |
validationReport->setParameter(lastValidTime); |
75 |
|
✗ |
return result; |
76 |
|
|
} |
77 |
|
|
|
78 |
|
✗ |
bool PathValidations::validate(ConfigurationIn_t q, |
79 |
|
|
ValidationReportPtr_t& report) { |
80 |
|
✗ |
for (auto pv : validations_) { |
81 |
|
✗ |
bool res(pv->validate(q, report)); |
82 |
|
✗ |
if (!res) return false; |
83 |
|
|
} |
84 |
|
✗ |
return true; |
85 |
|
|
} |
86 |
|
|
|
87 |
|
✗ |
PathValidations::PathValidations() {} |
88 |
|
|
} // namespace core |
89 |
|
|
} // namespace hpp |
90 |
|
|
|