GCC Code Coverage Report


Directory: ./
File: src/distance-between-points-in-bodies.cc
Date: 2025-05-05 12:19:30
Exec Total Coverage
Lines: 0 77 0.0%
Branches: 0 182 0.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015 CNRS
3 // Authors: Florent Lamiraux
4 //
5 //
6
7 // Redistribution and use in source and binary forms, with or without
8 // modification, are permitted provided that the following conditions are
9 // met:
10 //
11 // 1. Redistributions of source code must retain the above copyright
12 // notice, this list of conditions and the following disclaimer.
13 //
14 // 2. Redistributions in binary form must reproduce the above copyright
15 // notice, this list of conditions and the following disclaimer in the
16 // documentation and/or other materials provided with the distribution.
17 //
18 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
21 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
22 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
24 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
26 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
29 // DAMAGE.
30
31 #include <hpp/constraints/distance-between-points-in-bodies.hh>
32 #include <hpp/pinocchio/body.hh>
33 #include <hpp/pinocchio/collision-object.hh>
34 #include <hpp/pinocchio/device.hh>
35 #include <hpp/pinocchio/joint.hh>
36 #include <pinocchio/spatial/se3.hpp>
37
38 namespace hpp {
39 namespace constraints {
40
41 static void cross(const vector3_t& v, eigen::matrix3_t& m) {
42 m(0, 1) = -v[2];
43 m(1, 0) = v[2];
44 m(0, 2) = v[1];
45 m(2, 0) = -v[1];
46 m(1, 2) = -v[0];
47 m(2, 1) = v[0];
48 m(0, 0) = m(1, 1) = m(2, 2) = 0;
49 }
50
51 DistanceBetweenPointsInBodiesPtr_t DistanceBetweenPointsInBodies::create(
52 const std::string& name, const DevicePtr_t& robot, const JointPtr_t& joint1,
53 const JointPtr_t& joint2, const vector3_t& point1,
54 const vector3_t& point2) {
55 DistanceBetweenPointsInBodies* ptr = new DistanceBetweenPointsInBodies(
56 name, robot, joint1, joint2, point1, point2);
57 DistanceBetweenPointsInBodiesPtr_t shPtr(ptr);
58 return shPtr;
59 }
60
61 DistanceBetweenPointsInBodiesPtr_t DistanceBetweenPointsInBodies::create(
62 const std::string& name, const DevicePtr_t& robot, const JointPtr_t& joint1,
63 const vector3_t& point1, const vector3_t& point2) {
64 DistanceBetweenPointsInBodies* ptr =
65 new DistanceBetweenPointsInBodies(name, robot, joint1, point1, point2);
66 DistanceBetweenPointsInBodiesPtr_t shPtr(ptr);
67 return shPtr;
68 }
69
70 DistanceBetweenPointsInBodies::DistanceBetweenPointsInBodies(
71 const std::string& name, const DevicePtr_t& robot, const JointPtr_t& joint1,
72 const JointPtr_t& joint2, const vector3_t& point1, const vector3_t& point2)
73 : DifferentiableFunction(robot->configSize(), robot->numberDof(),
74 LiegroupSpace::R1(), name),
75 robot_(robot),
76 joint1_(joint1),
77 joint2_(joint2),
78 point1_(point1),
79 point2_(point2),
80 latestResult_(outputSpace()) {
81 assert(joint1);
82 global2_ = point2;
83 }
84
85 DistanceBetweenPointsInBodies::DistanceBetweenPointsInBodies(
86 const std::string& name, const DevicePtr_t& robot, const JointPtr_t& joint1,
87 const vector3_t& point1, const vector3_t& point2)
88 : DifferentiableFunction(robot->configSize(), robot->numberDof(),
89 LiegroupSpace::R1(), name),
90 robot_(robot),
91 joint1_(joint1),
92 joint2_(),
93 point1_(point1),
94 point2_(point2),
95 latestResult_(outputSpace()) {
96 assert(joint1);
97 global2_ = point2;
98 }
99
100 void DistanceBetweenPointsInBodies::impl_compute(
101 LiegroupElementRef result, ConfigurationIn_t argument) const {
102 if ((argument.rows() == latestArgument_.rows()) &&
103 (argument == latestArgument_)) {
104 result = latestResult_;
105 return;
106 }
107 robot_->currentConfiguration(argument);
108 robot_->computeForwardKinematics(pinocchio::JOINT_POSITION |
109 pinocchio::JACOBIAN);
110 global1_ = joint1_->currentTransformation().act(point1_);
111 if (joint2_) {
112 global2_ = joint2_->currentTransformation().act(point2_);
113 result.vector()[0] = (global2_ - global1_).norm();
114 } else {
115 result.vector()[0] = (global1_).norm();
116 }
117
118 latestArgument_ = argument;
119 latestResult_ = result;
120 }
121
122 void DistanceBetweenPointsInBodies::impl_jacobian(matrixOut_t jacobian,
123 ConfigurationIn_t arg) const {
124 LiegroupElement dist(outputSpace());
125 impl_compute(dist, arg);
126 const JointJacobian_t& J1(joint1_->jacobian());
127 const Transform3s& M1(joint1_->currentTransformation());
128 const matrix3_t& R1(M1.rotation());
129
130 // P1 - P2
131 vector3_t P1_minus_P2(global1_ - global2_);
132 // P1 - t1
133 vector3_t P1_minus_t1(global1_ - M1.translation());
134
135 // FIXME Remove me
136 eigen::matrix3_t P1_minus_t1_cross;
137 cross(P1_minus_t1, P1_minus_t1_cross);
138 assert(R1.colwise().cross(P1_minus_t1).isApprox(-P1_minus_t1_cross * R1));
139
140 // T ( )
141 // (P1-P2) ( J - [P1 - t1] J )
142 // ( 1 [0:3] x 1 [3:6] )
143 matrix_t tmp1(P1_minus_P2.transpose() * R1 * J1.topRows(3) +
144 P1_minus_P2.transpose() * R1.colwise().cross(P1_minus_t1) *
145 J1.bottomRows(3));
146 if (joint2_) {
147 const JointJacobian_t& J2(joint2_->jacobian());
148 const Transform3s& M2(joint2_->currentTransformation());
149 const matrix3_t& R2(M2.rotation());
150 // P2 - t2
151 vector3_t P2_minus_t2(global2_ - M2.translation());
152 // T ( )
153 // (P1-P2) ( J - [P1 - t1] J )
154 // ( 2 [0:3] x 2 [3:6] )
155 matrix_t tmp2(P1_minus_P2.transpose() * R2 * J2.topRows(3) +
156 P1_minus_P2.transpose() * R2.colwise().cross(P2_minus_t2) *
157 J2.bottomRows(3));
158 jacobian = (tmp1 - tmp2) / dist.vector()[0];
159 } else {
160 jacobian = tmp1 / dist.vector()[0];
161 }
162 }
163
164 } // namespace constraints
165 } // namespace hpp
166