Directory: | ./ |
---|---|
File: | include/hpp/constraints/explicit/implicit-function.hh |
Date: | 2025-05-05 12:19:30 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 12 | 16 | 75.0% |
Branches: | 20 | 34 | 58.8% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (c) 2015 - 2018 LAAS-CNRS | ||
2 | // Authors: Florent Lamiraux, Joseph Mirabel | ||
3 | // | ||
4 | |||
5 | // Redistribution and use in source and binary forms, with or without | ||
6 | // modification, are permitted provided that the following conditions are | ||
7 | // met: | ||
8 | // | ||
9 | // 1. Redistributions of source code must retain the above copyright | ||
10 | // notice, this list of conditions and the following disclaimer. | ||
11 | // | ||
12 | // 2. Redistributions in binary form must reproduce the above copyright | ||
13 | // notice, this list of conditions and the following disclaimer in the | ||
14 | // documentation and/or other materials provided with the distribution. | ||
15 | // | ||
16 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
17 | // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
18 | // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR | ||
19 | // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT | ||
20 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, | ||
21 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT | ||
22 | // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, | ||
23 | // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY | ||
24 | // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT | ||
25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE | ||
26 | // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH | ||
27 | // DAMAGE. | ||
28 | |||
29 | #ifndef HPP_CONSTRAINTS_EXPLICIT_IMPLICIT_FUNCTION_HH | ||
30 | #define HPP_CONSTRAINTS_EXPLICIT_IMPLICIT_FUNCTION_HH | ||
31 | |||
32 | #include <hpp/constraints/differentiable-function.hh> | ||
33 | #include <hpp/constraints/matrix-view.hh> | ||
34 | |||
35 | namespace hpp { | ||
36 | namespace constraints { | ||
37 | namespace explicit_ { | ||
38 | /// Function of the form q -> g (q_out) - f (q_in) | ||
39 | /// | ||
40 | /// where | ||
41 | /// \li q_out is a vector composed of configuration variables of | ||
42 | /// q, | ||
43 | /// \li q_in is the vector composed of other configuration variables of | ||
44 | /// q, | ||
45 | /// \li f, g are differentiable functions with values in a Lie group. | ||
46 | /// | ||
47 | /// This class is mainly used to create hpp::constraints::Explicit | ||
48 | /// instances. | ||
49 | class ImplicitFunction : public DifferentiableFunction { | ||
50 | public: | ||
51 | typedef shared_ptr<ImplicitFunction> Ptr_t; | ||
52 | /// create instance and return shared pointer | ||
53 | /// | ||
54 | /// \param configSpace input space of this function - usually a robot | ||
55 | /// configuration space, | ||
56 | /// \param function function f, | ||
57 | /// \param inputConf set of indices defining q_in, | ||
58 | /// \param inputVelocity set of indices defining q_in derivative, | ||
59 | /// \param outputConf set of indices defining q_out | ||
60 | /// \param outputVelocity set of indices defining q_out derivative | ||
61 | /// | ||
62 | |||
63 | static Ptr_t create(const LiegroupSpacePtr_t& configSpace, | ||
64 | const DifferentiableFunctionPtr_t& function, | ||
65 | const segments_t& inputConf, const segments_t& outputConf, | ||
66 | const segments_t& inputVelocity, | ||
67 | const segments_t& outputVelocity); | ||
68 | |||
69 | /// Get function f that maps input variables to output variables | ||
70 | const DifferentiableFunctionPtr_t& inputToOutput() const; | ||
71 | |||
72 | protected: | ||
73 | /// Constructor | ||
74 | /// \param configSpace input space of this function - usually a robot | ||
75 | /// configuration space, | ||
76 | /// \param function function f, | ||
77 | /// \param inputConf set of indices defining q_in, | ||
78 | /// \param inputVelocity set of indices defining q_in derivative, | ||
79 | /// \param outputConf set of indices defining q_out | ||
80 | /// \param outputVelocity set of indices defining q_out derivative | ||
81 | ImplicitFunction(const LiegroupSpacePtr_t& configSpace, | ||
82 | const DifferentiableFunctionPtr_t& function, | ||
83 | const segments_t& inputConf, const segments_t& outputConf, | ||
84 | const segments_t& inputVelocity, | ||
85 | const segments_t& outputVelocity); | ||
86 | /// Compute g (q_out) - f (q_in) | ||
87 | void impl_compute(LiegroupElementRef result, vectorIn_t argument) const; | ||
88 | |||
89 | /// Compute Jacobian of g (q_out) - f (q_in) with respect to q. | ||
90 | void impl_jacobian(matrixOut_t jacobian, vectorIn_t arg) const; | ||
91 | |||
92 | 22 | bool isEqual(const DifferentiableFunction& other) const { | |
93 | const ImplicitFunction& castother = | ||
94 |
2/2✓ Branch 0 taken 15 times.
✓ Branch 1 taken 7 times.
|
22 | dynamic_cast<const ImplicitFunction&>(other); |
95 |
2/2✓ Branch 1 taken 2 times.
✓ Branch 2 taken 13 times.
|
15 | if (!DifferentiableFunction::isEqual(other)) return false; |
96 | |||
97 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 13 times.
|
13 | if (robot_ != castother.robot_) return false; |
98 |
2/2✓ Branch 1 taken 9 times.
✓ Branch 2 taken 4 times.
|
13 | if (inputToOutput_ != castother.inputToOutput_) return false; |
99 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 4 times.
|
4 | if (inputConfIntervals_.rows() != castother.inputConfIntervals_.rows()) |
100 | ✗ | return false; | |
101 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 4 times.
|
4 | if (outputConfIntervals_.rows() != castother.outputConfIntervals_.rows()) |
102 | ✗ | return false; | |
103 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 4 times.
|
4 | if (inputDerivIntervals_.rows() != castother.inputDerivIntervals_.rows()) |
104 | ✗ | return false; | |
105 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 4 times.
|
4 | if (outputDerivIntervals_.rows() != castother.outputDerivIntervals_.rows()) |
106 | ✗ | return false; | |
107 | |||
108 | 4 | return true; | |
109 | } | ||
110 | |||
111 | /// Return pair of joints the relative pose between which | ||
112 | /// modifies the function value if any | ||
113 | /// | ||
114 | /// Currently checks if the implicit function specifies a joint | ||
115 | /// where | ||
116 | /// \li q_out is a vector corresponding to only 1 joint | ||
117 | /// \li q_in is an empty vector (since f is constant and specifies | ||
118 | /// the whole or part of the pose of the joint) | ||
119 | /// | ||
120 | /// \param robot the robot the constraints are applied on, | ||
121 | /// \return pair of pointers to the lock joint and its parent joint, | ||
122 | /// arranged in order of increasing joint index, or a pair of empty | ||
123 | /// shared pointers if the implicit function does not specify a locked | ||
124 | /// joint. | ||
125 | std::pair<JointConstPtr_t, JointConstPtr_t> dependsOnRelPoseBetween( | ||
126 | DeviceConstPtr_t robot) const; | ||
127 | |||
128 | private: | ||
129 | void computeJacobianBlocks(); | ||
130 | |||
131 | DevicePtr_t robot_; | ||
132 | DifferentiableFunctionPtr_t inputToOutput_; | ||
133 | Eigen::RowBlockIndices inputConfIntervals_; | ||
134 | Eigen::RowBlockIndices outputConfIntervals_; | ||
135 | Eigen::RowBlockIndices inputDerivIntervals_; | ||
136 | Eigen::RowBlockIndices outputDerivIntervals_; | ||
137 | std::vector<Eigen::MatrixBlocks<false, false> > outJacobian_; | ||
138 | std::vector<Eigen::MatrixBlocks<false, false> > inJacobian_; | ||
139 | mutable vector_t qIn_; | ||
140 | mutable LiegroupElement f_qIn_, qOut_; | ||
141 | mutable LiegroupElement result_; | ||
142 | // Jacobian of explicit function | ||
143 | mutable matrix_t Jf_; | ||
144 | |||
145 |
9/18✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
|
1 | ImplicitFunction() {} |
146 | HPP_SERIALIZABLE(); | ||
147 | }; // class ImplicitFunction | ||
148 | |||
149 | } // namespace explicit_ | ||
150 | } // namespace constraints | ||
151 | } // namespace hpp | ||
152 | |||
153 | 12 | BOOST_CLASS_EXPORT_KEY(hpp::constraints::explicit_::ImplicitFunction) | |
154 | |||
155 | #endif // HPP_CONSTRAINTS_EXPLICIT_IMPLICIT_FUNCTION_HH | ||
156 |