Line |
Branch |
Exec |
Source |
1 |
|
|
// |
2 |
|
|
// Copyright (c) 2014 CNRS |
3 |
|
|
// Authors: Florent Lamiraux |
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 |
|
|
#ifndef HPP_CORE_PATH_VALIDATION_HH |
31 |
|
|
#define HPP_CORE_PATH_VALIDATION_HH |
32 |
|
|
|
33 |
|
|
#include <hpp/core/config.hh> |
34 |
|
|
#include <hpp/core/fwd.hh> |
35 |
|
|
#include <hpp/core/relative-motion.hh> |
36 |
|
|
|
37 |
|
|
namespace hpp { |
38 |
|
|
namespace core { |
39 |
|
|
/// \addtogroup validation |
40 |
|
|
/// \{ |
41 |
|
|
|
42 |
|
|
/// Abstraction of path validation |
43 |
|
|
/// |
44 |
|
|
/// Instances of this class compute the latest valid configuration along |
45 |
|
|
/// a path. |
46 |
|
|
/// |
47 |
|
|
/// Method \code validate(ConfigurationIn_t q) \endcode is provided to |
48 |
|
|
/// validate single configurations. It is particularly useful to test |
49 |
|
|
/// the initial and goal configurations of a path planning problem using |
50 |
|
|
/// this path validation. |
51 |
|
|
class HPP_CORE_DLLAPI PathValidation { |
52 |
|
|
public: |
53 |
|
|
/// Compute the largest valid interval starting from the path beginning |
54 |
|
|
/// |
55 |
|
|
/// \param path the path to check for validity, |
56 |
|
|
/// \param reverse if true check from the end, |
57 |
|
|
/// \retval the extracted valid part of the path, pointer to path if |
58 |
|
|
/// path is valid. |
59 |
|
|
/// \retval report information about the validation process. A report |
60 |
|
|
/// is allocated if the path is not valid. |
61 |
|
|
/// \return whether the whole path is valid. |
62 |
|
|
virtual bool validate(const PathPtr_t& path, bool reverse, |
63 |
|
|
PathPtr_t& validPart, |
64 |
|
|
PathValidationReportPtr_t& report) = 0; |
65 |
|
|
|
66 |
|
|
/// Validate a single configuration |
67 |
|
|
/// \param q input configuration, |
68 |
|
|
/// \retval report validation report. |
69 |
|
|
/// The default implementation builds a straight path of length 0 |
70 |
|
|
/// with the input configuration and validates the path. |
71 |
|
|
virtual bool validate(ConfigurationIn_t q, ValidationReportPtr_t& report); |
72 |
|
122 |
virtual ~PathValidation() {}; |
73 |
|
|
|
74 |
|
|
protected: |
75 |
|
70 |
PathValidation() {} |
76 |
|
|
}; // class PathValidation |
77 |
|
|
/// \} |
78 |
|
|
} // namespace core |
79 |
|
|
} // namespace hpp |
80 |
|
|
|
81 |
|
|
#endif // HPP_CORE_PATH_VALIDATION_HH |
82 |
|
|
|