| Directory: | ./ |
|---|---|
| File: | src/generic-transformation.cc |
| Date: | 2025-05-05 12:19:30 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 144 | 150 | 96.0% |
| Branches: | 140 | 277 | 50.5% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // Copyright (c) 2016, Joseph Mirabel | ||
| 2 | // Authors: Joseph Mirabel (joseph.mirabel@laas.fr) | ||
| 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 | #include <boost/serialization/vector.hpp> | ||
| 30 | #include <hpp/constraints/generic-transformation.hh> | ||
| 31 | #include <hpp/constraints/macros.hh> | ||
| 32 | #include <hpp/pinocchio/configuration.hh> | ||
| 33 | #include <hpp/pinocchio/device.hh> | ||
| 34 | #include <hpp/pinocchio/serialization.hh> | ||
| 35 | #include <hpp/util/indent.hh> | ||
| 36 | #include <hpp/util/serialization.hh> | ||
| 37 | #include <pinocchio/serialization/se3.hpp> | ||
| 38 | |||
| 39 | #include "generic-transformation/helper.hh" | ||
| 40 | #include "serialization.hh" | ||
| 41 | |||
| 42 | namespace hpp { | ||
| 43 | namespace constraints { | ||
| 44 | template <bool pos, bool ori, bool ose3> | ||
| 45 | 188 | LiegroupSpacePtr_t liegroupSpace(const std::vector<bool>& mask) { | |
| 46 |
2/4✓ Branch 1 taken 77 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 77 times.
✗ Branch 6 not taken.
|
308 | if (!ose3) return LiegroupSpace::Rn(size(mask)); |
| 47 | assert(ori); | ||
| 48 |
6/12✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 17 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 17 times.
✗ Branch 7 not taken.
✓ Branch 8 taken 17 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 17 times.
✗ Branch 12 not taken.
✓ Branch 13 taken 17 times.
✗ Branch 14 not taken.
|
34 | assert(mask[(pos ? 3 : 0) + 0] && mask[(pos ? 3 : 0) + 1] && |
| 49 | mask[(pos ? 3 : 0) + 2] && | ||
| 50 | "Full orientation is necessary to output R3xSO3 / SO3 error"); | ||
| 51 |
1/2✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
|
34 | const size_type nTranslation = size(mask) - 3; |
| 52 |
1/2✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
|
34 | LiegroupSpacePtr_t SO3 = LiegroupSpace::SO3(); |
| 53 |
2/5✓ Branch 0 taken 3 times.
✗ Branch 1 not taken.
✗ Branch 2 not taken.
✓ Branch 3 taken 14 times.
✗ Branch 4 not taken.
|
34 | switch (nTranslation) { |
| 54 | 6 | case 0: | |
| 55 | 6 | return SO3; | |
| 56 | ✗ | case 1: | |
| 57 | ✗ | return LiegroupSpace::R1() * SO3; | |
| 58 | ✗ | case 2: | |
| 59 | ✗ | return LiegroupSpace::R2() * SO3; | |
| 60 | 28 | case 3: | |
| 61 |
1/2✓ Branch 1 taken 14 times.
✗ Branch 2 not taken.
|
28 | return LiegroupSpace::R3xSO3(); |
| 62 | ✗ | default: | |
| 63 | ✗ | throw std::logic_error("This should not happen. Invalid mask."); | |
| 64 | } | ||
| 65 | } | ||
| 66 | |||
| 67 | template <bool pos, bool ori, bool ose3> | ||
| 68 | 188 | inline Eigen::RowBlockIndices indices(const std::vector<bool>& mask) { | |
| 69 |
1/2✓ Branch 2 taken 94 times.
✗ Branch 3 not taken.
|
188 | ArrayXb _mask(mask.size() + (ose3 ? 1 : 0)); |
| 70 |
4/6✓ Branch 1 taken 399 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 399 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 399 times.
✓ Branch 8 taken 94 times.
|
986 | for (std::size_t i = 0; i < mask.size(); ++i) _mask[i] = mask[i]; |
| 71 | if (ose3) { | ||
| 72 | assert(ori); | ||
| 73 |
6/12✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 17 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 17 times.
✗ Branch 7 not taken.
✓ Branch 8 taken 17 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 17 times.
✗ Branch 12 not taken.
✓ Branch 13 taken 17 times.
✗ Branch 14 not taken.
|
34 | assert(mask[(pos ? 3 : 0) + 0] && mask[(pos ? 3 : 0) + 1] && |
| 74 | mask[(pos ? 3 : 0) + 2] && | ||
| 75 | "Full orientation is necessary to output R3xSO3 / SO3 error"); | ||
| 76 |
1/2✓ Branch 2 taken 17 times.
✗ Branch 3 not taken.
|
34 | _mask[_mask.size() - 1] = true; |
| 77 | } | ||
| 78 | return Eigen::RowBlockIndices( | ||
| 79 |
2/4✓ Branch 1 taken 94 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 94 times.
✗ Branch 5 not taken.
|
376 | Eigen::BlockIndex::fromLogicalExpression(_mask)); |
| 80 | 188 | } | |
| 81 | |||
| 82 | 56 | void GenericTransformationModel<true>::setJoint1(const JointConstPtr_t& j) { | |
| 83 |
5/6✓ Branch 1 taken 52 times.
✓ Branch 2 taken 4 times.
✓ Branch 5 taken 52 times.
✗ Branch 6 not taken.
✓ Branch 7 taken 52 times.
✓ Branch 8 taken 4 times.
|
56 | if (j && j->index() > 0) |
| 84 | 52 | joint1 = j; | |
| 85 | else | ||
| 86 | 4 | joint1.reset(); | |
| 87 |
3/4✓ Branch 1 taken 52 times.
✓ Branch 2 taken 4 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 52 times.
|
56 | assert(!joint1 || joint1->index()); |
| 88 | 56 | } | |
| 89 | |||
| 90 | template <int _Options> | ||
| 91 | 56 | std::ostream& GenericTransformation<_Options>::print(std::ostream& os) const { | |
| 92 | os << (IsRelative ? "Relative" : "") | ||
| 93 | << (ComputePosition ? (ComputeOrientation ? "Transformation" : "Position") | ||
| 94 | : "Orientation") | ||
| 95 | 56 | << ": " << name() << ", active dof: " | |
| 96 |
2/4✓ Branch 2 taken 28 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
|
56 | << pretty_print(BlockIndex::fromLogicalExpression(activeParameters_)) |
| 97 |
2/4✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 28 times.
✗ Branch 5 not taken.
|
56 | << incindent << iendl |
| 98 |
11/26✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 15 times.
✓ Branch 5 taken 13 times.
✗ Branch 6 not taken.
✓ Branch 7 taken 15 times.
✓ Branch 8 taken 13 times.
✗ Branch 9 not taken.
✓ Branch 10 taken 15 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 15 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 15 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✗ Branch 22 not taken.
✓ Branch 24 taken 15 times.
✗ Branch 25 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 15 times.
✓ Branch 30 taken 15 times.
✗ Branch 31 not taken.
✗ Branch 36 not taken.
✗ Branch 37 not taken.
✗ Branch 39 not taken.
✗ Branch 40 not taken.
|
112 | << "Joint1: " << ((IsRelative && joint1()) ? joint1()->name() : "World") |
| 99 |
4/8✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 28 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 28 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 28 times.
✗ Branch 11 not taken.
|
56 | << iendl << "Frame in joint 1" << incindent << iendl; |
| 100 | 56 | pinocchio::display(os, frame1InJoint1()) | |
| 101 | 56 | << decindent << iendl | |
| 102 |
12/22✓ Branch 3 taken 22 times.
✓ Branch 4 taken 6 times.
✓ Branch 6 taken 22 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 22 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 22 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 6 times.
✓ Branch 27 taken 22 times.
✓ Branch 29 taken 22 times.
✓ Branch 30 taken 6 times.
✗ Branch 34 not taken.
✗ Branch 35 not taken.
✗ Branch 37 not taken.
✗ Branch 38 not taken.
|
112 | << "Joint2: " << (joint2() ? joint2()->name() : "World") << iendl |
| 103 |
3/6✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 28 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 28 times.
✗ Branch 8 not taken.
|
56 | << "Frame in joint 2" << incindent << iendl; |
| 104 | 56 | pinocchio::display(os, frame2InJoint2()) << decindent << iendl << "mask: "; | |
| 105 |
2/2✓ Branch 3 taken 108 times.
✓ Branch 4 taken 28 times.
|
272 | for (size_type i = 0; i < DerSize; ++i) os << mask_[i] << ", "; |
| 106 | 56 | return os << decindent; | |
| 107 | } | ||
| 108 | |||
| 109 | template <int _Options> | ||
| 110 | typename GenericTransformation<_Options>::Ptr_t | ||
| 111 | 58 | GenericTransformation<_Options>::create(const std::string& name, | |
| 112 | const DevicePtr_t& robot, | ||
| 113 | const JointConstPtr_t& joint2, | ||
| 114 | const Transform3s& reference, | ||
| 115 | std::vector<bool> mask) { | ||
| 116 | 116 | GenericTransformation<_Options>* ptr = | |
| 117 |
2/4✓ Branch 1 taken 29 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 29 times.
✗ Branch 5 not taken.
|
58 | new GenericTransformation<_Options>(name, robot, mask); |
| 118 |
1/2✓ Branch 2 taken 29 times.
✗ Branch 3 not taken.
|
58 | ptr->joint1(JointConstPtr_t()); |
| 119 | 58 | ptr->joint2(joint2); | |
| 120 | 58 | ptr->reference(reference); | |
| 121 | 58 | Ptr_t shPtr(ptr); | |
| 122 |
1/2✓ Branch 2 taken 29 times.
✗ Branch 3 not taken.
|
58 | ptr->init(shPtr); |
| 123 | 58 | return shPtr; | |
| 124 | } | ||
| 125 | |||
| 126 | template <int _Options> | ||
| 127 | typename GenericTransformation<_Options>::Ptr_t | ||
| 128 | 18 | GenericTransformation<_Options>::create( | |
| 129 | const std::string& name, const DevicePtr_t& robot, | ||
| 130 | /* World frame */ const JointConstPtr_t& joint2, | ||
| 131 | const Transform3s& frame2, const Transform3s& frame1, | ||
| 132 | std::vector<bool> mask) { | ||
| 133 | 36 | GenericTransformation<_Options>* ptr = | |
| 134 |
2/4✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 9 times.
✗ Branch 5 not taken.
|
18 | new GenericTransformation<_Options>(name, robot, mask); |
| 135 |
1/2✓ Branch 2 taken 9 times.
✗ Branch 3 not taken.
|
18 | ptr->joint1(JointConstPtr_t()); |
| 136 | 18 | ptr->joint2(joint2); | |
| 137 | 18 | ptr->frame1InJoint1(frame1); | |
| 138 | 18 | ptr->frame2InJoint2(frame2); | |
| 139 | 18 | Ptr_t shPtr(ptr); | |
| 140 | 18 | return shPtr; | |
| 141 | } | ||
| 142 | |||
| 143 | template <int _Options> | ||
| 144 | typename GenericTransformation<_Options>::Ptr_t | ||
| 145 | 26 | GenericTransformation<_Options>::create(const std::string& name, | |
| 146 | const DevicePtr_t& robot, | ||
| 147 | const JointConstPtr_t& joint1, | ||
| 148 | const JointConstPtr_t& joint2, | ||
| 149 | const Transform3s& reference, | ||
| 150 | std::vector<bool> mask) { | ||
| 151 | 52 | GenericTransformation<_Options>* ptr = | |
| 152 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
26 | new GenericTransformation<_Options>(name, robot, mask); |
| 153 | 26 | ptr->joint1(joint1); | |
| 154 | 26 | ptr->joint2(joint2); | |
| 155 | 26 | ptr->reference(reference); | |
| 156 | 26 | Ptr_t shPtr(ptr); | |
| 157 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
26 | ptr->init(shPtr); |
| 158 | 26 | return shPtr; | |
| 159 | } | ||
| 160 | |||
| 161 | template <int _Options> | ||
| 162 | typename GenericTransformation<_Options>::Ptr_t | ||
| 163 | 86 | GenericTransformation<_Options>::create(const std::string& name, | |
| 164 | const DevicePtr_t& robot, | ||
| 165 | const JointConstPtr_t& joint1, | ||
| 166 | const JointConstPtr_t& joint2, | ||
| 167 | const Transform3s& frame1, | ||
| 168 | const Transform3s& frame2, | ||
| 169 | std::vector<bool> mask) { | ||
| 170 | 172 | GenericTransformation<_Options>* ptr = | |
| 171 |
2/4✓ Branch 1 taken 43 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 43 times.
✗ Branch 5 not taken.
|
86 | new GenericTransformation<_Options>(name, robot, mask); |
| 172 | 86 | ptr->joint1(joint1); | |
| 173 | 86 | ptr->joint2(joint2); | |
| 174 | 86 | ptr->frame1InJoint1(frame1); | |
| 175 | 86 | ptr->frame2InJoint2(frame2); | |
| 176 | 86 | Ptr_t shPtr(ptr); | |
| 177 | 86 | return shPtr; | |
| 178 | } | ||
| 179 | |||
| 180 | template <int _Options> | ||
| 181 | 188 | GenericTransformation<_Options>::GenericTransformation(const std::string& name, | |
| 182 | const DevicePtr_t& robot, | ||
| 183 | std::vector<bool> mask) | ||
| 184 | : DifferentiableFunction( | ||
| 185 | robot->configSize(), robot->numberDof(), | ||
| 186 | liegroupSpace<(bool)ComputePosition, (bool)ComputeOrientation, | ||
| 187 | (bool)OutputR3xSO3>(mask), | ||
| 188 | name), | ||
| 189 | 188 | robot_(robot), | |
| 190 |
2/4✓ Branch 2 taken 94 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 94 times.
✗ Branch 9 not taken.
|
188 | m_(robot->numberDof() - robot->extraConfigSpace().dimension()), |
| 191 |
1/2✓ Branch 1 taken 94 times.
✗ Branch 2 not taken.
|
188 | Vindices_(indices<(bool)ComputePosition, (bool)ComputeOrientation, |
| 192 | (bool)OutputR3xSO3>(mask)), | ||
| 193 |
5/10✓ Branch 2 taken 94 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 94 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 94 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 94 times.
✗ Branch 14 not taken.
✓ Branch 19 taken 94 times.
✗ Branch 20 not taken.
|
376 | mask_(mask) { |
| 194 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 94 times.
|
188 | assert(mask.size() == DerSize); |
| 195 | 188 | std::size_t iOri = 0; | |
| 196 | 188 | m_.rowOri = 0; | |
| 197 | if (ComputePosition) { | ||
| 198 |
2/2✓ Branch 0 taken 180 times.
✓ Branch 1 taken 60 times.
|
480 | for (size_type i = 0; i < 3; ++i) |
| 199 |
3/4✓ Branch 1 taken 180 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 178 times.
✓ Branch 4 taken 2 times.
|
360 | if (mask_[i]) m_.rowOri++; |
| 200 | 120 | m_.fullPos = (m_.rowOri == 3); | |
| 201 | 120 | iOri = 3; | |
| 202 | } else | ||
| 203 | 68 | m_.fullPos = false; | |
| 204 | if (ComputeOrientation) | ||
| 205 |
7/12✓ Branch 1 taken 73 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 70 times.
✓ Branch 4 taken 3 times.
✓ Branch 6 taken 70 times.
✗ Branch 7 not taken.
✓ Branch 8 taken 70 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 70 times.
✗ Branch 12 not taken.
✓ Branch 13 taken 70 times.
✗ Branch 14 not taken.
|
146 | m_.fullOri = mask_[iOri + 0] && mask_[iOri + 1] && mask_[iOri + 2]; |
| 206 | else | ||
| 207 | 42 | m_.fullOri = false; | |
| 208 | 188 | } | |
| 209 | |||
| 210 | template <int _Options> | ||
| 211 | 460 | inline void GenericTransformation<_Options>::computeActiveParams() { | |
| 212 |
1/2✓ Branch 1 taken 230 times.
✗ Branch 2 not taken.
|
460 | activeParameters_.setConstant(false); |
| 213 |
1/2✓ Branch 1 taken 230 times.
✗ Branch 2 not taken.
|
460 | activeDerivativeParameters_.setConstant(false); |
| 214 | |||
| 215 |
2/4✓ Branch 1 taken 230 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 230 times.
✗ Branch 5 not taken.
|
460 | setActiveParameters(robot_, joint1(), joint2(), activeParameters_, |
| 216 | 460 | activeDerivativeParameters_); | |
| 217 | 460 | } | |
| 218 | |||
| 219 | template <int _Options> | ||
| 220 | 49370 | void GenericTransformation<_Options>::impl_compute( | |
| 221 | LiegroupElementRef result, ConfigurationIn_t argument) const { | ||
| 222 | GTDataV<IsRelative, (bool)ComputePosition, (bool)ComputeOrientation, | ||
| 223 | (bool)OutputR3xSO3> | ||
| 224 |
1/2✓ Branch 1 taken 24707 times.
✗ Branch 2 not taken.
|
49370 | data(m_, robot_); |
| 225 | |||
| 226 |
2/4✓ Branch 1 taken 24709 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24706 times.
✗ Branch 5 not taken.
|
49414 | data.device.currentConfiguration(argument); |
| 227 |
1/2✓ Branch 1 taken 24707 times.
✗ Branch 2 not taken.
|
49416 | data.device.computeForwardKinematics(pinocchio::JOINT_POSITION); |
| 228 | compute<IsRelative, (bool)ComputePosition, (bool)ComputeOrientation, | ||
| 229 |
1/2✓ Branch 1 taken 24705 times.
✗ Branch 2 not taken.
|
49414 | (bool)OutputR3xSO3>::error(data); |
| 230 | |||
| 231 |
2/4✓ Branch 1 taken 24704 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 24704 times.
✗ Branch 6 not taken.
|
49410 | result.vector() = Vindices_.rview(data.value); |
| 232 |
2/4✓ Branch 1 taken 24703 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 24703 times.
|
49408 | assert(hpp::pinocchio::checkNormalized(result)); |
| 233 | 49406 | } | |
| 234 | |||
| 235 | template <int _Options> | ||
| 236 | 7172 | void GenericTransformation<_Options>::impl_jacobian( | |
| 237 | matrixOut_t jacobian, ConfigurationIn_t arg) const { | ||
| 238 | // TODO there is still a little bit a memory which is dynamically | ||
| 239 | // allocated in GTDataJ. At the moment, this allocation is necessary to | ||
| 240 | // support multithreadind. To avoid it, DeviceData should provide some | ||
| 241 | // a temporary buffer to pass to an Eigen::Map | ||
| 242 | { | ||
| 243 | GTDataJ<IsRelative, (bool)ComputePosition, (bool)ComputeOrientation, | ||
| 244 | (bool)OutputR3xSO3> | ||
| 245 |
1/2✓ Branch 1 taken 3585 times.
✗ Branch 2 not taken.
|
7172 | data(m_, robot_); |
| 246 | |||
| 247 |
2/4✓ Branch 1 taken 3584 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3584 times.
✗ Branch 5 not taken.
|
7170 | data.device.currentConfiguration(arg); |
| 248 |
1/2✓ Branch 1 taken 3586 times.
✗ Branch 2 not taken.
|
7170 | data.device.computeForwardKinematics(pinocchio::JOINT_POSITION | |
| 249 | pinocchio::JACOBIAN); | ||
| 250 | compute<IsRelative, (bool)ComputePosition, (bool)ComputeOrientation, | ||
| 251 |
1/2✓ Branch 1 taken 3585 times.
✗ Branch 2 not taken.
|
7172 | (bool)OutputR3xSO3>::error(data); |
| 252 | compute<IsRelative, (bool)ComputePosition, (bool)ComputeOrientation, | ||
| 253 |
2/4✓ Branch 1 taken 3585 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3581 times.
✗ Branch 5 not taken.
|
7170 | (bool)OutputR3xSO3>::jacobian(data, jacobian, mask_); |
| 254 | 7162 | } | |
| 255 | |||
| 256 | #ifdef CHECK_JACOBIANS | ||
| 257 | const value_type eps = std::sqrt(Eigen::NumTraits<value_type>::epsilon()); | ||
| 258 | matrix_t Jfd(outputDerivativeSize(), inputDerivativeSize()); | ||
| 259 | Jfd.setZero(); | ||
| 260 | finiteDifferenceCentral(Jfd, arg, robot_, eps); | ||
| 261 | size_type row, col; | ||
| 262 | value_type maxError = (jacobian - Jfd).cwiseAbs().maxCoeff(&row, &col); | ||
| 263 | if (maxError > std::sqrt(eps)) { | ||
| 264 | hppDout( | ||
| 265 | error, "Jacobian of " | ||
| 266 | << name() | ||
| 267 | << " does not match central finite difference. " | ||
| 268 | "DOF " | ||
| 269 | << col << " at row " << row << ": " << maxError << " > " | ||
| 270 | << /* HESSIAN_MAXIMUM_COEF << " * " << */ std::sqrt(eps)); | ||
| 271 | hppDnum(error, "Jacobian is" << iendl << jacobian << iendl | ||
| 272 | << "Finite diff is" << iendl << Jfd << iendl | ||
| 273 | << "Difference is" << iendl | ||
| 274 | << (jacobian - Jfd)); | ||
| 275 | } | ||
| 276 | #endif | ||
| 277 | 7172 | } | |
| 278 | |||
| 279 | template <int _Options> | ||
| 280 | template <class Archive> | ||
| 281 | 44 | void GenericTransformation<_Options>::serialize(Archive& ar, | |
| 282 | const unsigned int version) { | ||
| 283 | (void)version; | ||
| 284 |
1/2✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
|
44 | ar& boost::serialization::make_nvp( |
| 285 | 44 | "base", boost::serialization::base_object<DifferentiableFunction>(*this)); | |
| 286 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& BOOST_SERIALIZATION_NVP(robot_); |
| 287 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& BOOST_SERIALIZATION_NVP(m_); |
| 288 |
1/2✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
|
44 | ar& boost::serialization::make_nvp("mask_", |
| 289 | 44 | const_cast<std::vector<bool>&>(mask_)); | |
| 290 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& BOOST_SERIALIZATION_NVP(self_); |
| 291 | } | ||
| 292 | |||
| 293 | /// Force instanciation of relevant classes | ||
| 294 | template class GenericTransformation<PositionBit | OrientationBit>; | ||
| 295 | template class GenericTransformation<PositionBit>; | ||
| 296 | template class GenericTransformation<OrientationBit>; | ||
| 297 | template class GenericTransformation<RelativeBit | PositionBit | | ||
| 298 | OrientationBit>; | ||
| 299 | template class GenericTransformation<RelativeBit | PositionBit>; | ||
| 300 | template class GenericTransformation<RelativeBit | OrientationBit>; | ||
| 301 | |||
| 302 | template class GenericTransformation<OutputR3xSO3Bit | PositionBit | | ||
| 303 | OrientationBit>; | ||
| 304 | // template class GenericTransformation< OutputR3xSO3Bit | PositionBit >; | ||
| 305 | template class GenericTransformation<OutputR3xSO3Bit | OrientationBit>; | ||
| 306 | template class GenericTransformation<OutputR3xSO3Bit | RelativeBit | | ||
| 307 | PositionBit | OrientationBit>; | ||
| 308 | // template class GenericTransformation< OutputR3xSO3Bit | RelativeBit | | ||
| 309 | // PositionBit >; | ||
| 310 | template class GenericTransformation<OutputR3xSO3Bit | RelativeBit | | ||
| 311 | OrientationBit>; | ||
| 312 | |||
| 313 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::Position); | ||
| 314 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::Orientation); | ||
| 315 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::Transformation); | ||
| 316 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::RelativePosition); | ||
| 317 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::RelativeOrientation); | ||
| 318 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::RelativeTransformation); | ||
| 319 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::TransformationR3xSO3); | ||
| 320 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::RelativeTransformationR3xSO3); | ||
| 321 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::OrientationSO3); | ||
| 322 | HPP_SERIALIZATION_IMPLEMENT(hpp::constraints::RelativeOrientationSO3); | ||
| 323 | } // namespace constraints | ||
| 324 | } // namespace hpp | ||
| 325 | |||
| 326 | namespace boost { | ||
| 327 | namespace serialization { | ||
| 328 | using hpp::constraints::GenericTransformationModel; | ||
| 329 | |||
| 330 | #define _make_nvp(attr) make_nvp(#attr, m.attr) | ||
| 331 | template <class Archive> | ||
| 332 | 44 | inline void serialize(Archive& ar, GenericTransformationModel<false>& m, | |
| 333 | const unsigned int version) { | ||
| 334 | (void)version; | ||
| 335 | 44 | hpp::constraints::internal::serialize_joint(ar, "joint2", m.joint2); | |
| 336 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(R1isID); |
| 337 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(R2isID); |
| 338 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(t1isZero); |
| 339 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(t2isZero); |
| 340 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(F1inJ1); |
| 341 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(F2inJ2); |
| 342 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(fullPos); |
| 343 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(fullOri); |
| 344 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& _make_nvp(rowOri); |
| 345 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
44 | ar& make_nvp("cols", const_cast<hpp::constraints::size_type&>(m.cols)); |
| 346 | } | ||
| 347 | |||
| 348 | template <class Archive> | ||
| 349 | 24 | inline void serialize(Archive& ar, GenericTransformationModel<true>& m, | |
| 350 | const unsigned int version) { | ||
| 351 | (void)version; | ||
| 352 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | ar& make_nvp( |
| 353 | "base", | ||
| 354 | 24 | boost::serialization::base_object<GenericTransformationModel<false> >(m)); | |
| 355 | 24 | hpp::constraints::internal::serialize_joint(ar, "joint1", m.joint1); | |
| 356 | } | ||
| 357 | } // namespace serialization | ||
| 358 | } // namespace boost | ||
| 359 | |||
| 360 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::Position) | |
| 361 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::Orientation) | |
| 362 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::Transformation) | |
| 363 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::RelativePosition) | |
| 364 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::RelativeOrientation) | |
| 365 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::RelativeTransformation) | |
| 366 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::TransformationR3xSO3) | |
| 367 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::RelativeTransformationR3xSO3) | |
| 368 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::OrientationSO3) | |
| 369 | 12 | BOOST_CLASS_EXPORT(hpp::constraints::RelativeOrientationSO3) | |
| 370 |