Blender V5.0
IK_Math.h
Go to the documentation of this file.
1/* SPDX-FileCopyrightText: 2001-2002 NaN Holding BV. All rights reserved.
2 *
3 * SPDX-License-Identifier: GPL-2.0-or-later */
4
8
9#pragma once
10
11#include <Eigen/Core>
12#include <Eigen/Geometry>
13
14#include <algorithm>
15#include <cmath>
16
17using Eigen::Affine3d;
18using Eigen::Matrix3d;
19using Eigen::MatrixXd;
20using Eigen::Vector3d;
21using Eigen::VectorXd;
22
23static const double IK_EPSILON = 1e-20;
24
25static inline bool FuzzyZero(double x)
26{
27 return fabs(x) < IK_EPSILON;
28}
29
30static inline double Clamp(const double x, const double min, const double max)
31{
32 return (x < min) ? min : (x > max) ? max : x;
33}
34
35static inline Eigen::Matrix3d CreateMatrix(double xx,
36 double xy,
37 double xz,
38 double yx,
39 double yy,
40 double yz,
41 double zx,
42 double zy,
43 double zz)
44{
45 Eigen::Matrix3d M;
46 M(0, 0) = xx;
47 M(0, 1) = xy;
48 M(0, 2) = xz;
49 M(1, 0) = yx;
50 M(1, 1) = yy;
51 M(1, 2) = yz;
52 M(2, 0) = zx;
53 M(2, 1) = zy;
54 M(2, 2) = zz;
55 return M;
56}
57
58static inline Eigen::Matrix3d RotationMatrix(double sine, double cosine, int axis)
59{
60 if (axis == 0) {
61 return CreateMatrix(1.0, 0.0, 0.0, 0.0, cosine, -sine, 0.0, sine, cosine);
62 }
63 if (axis == 1) {
64 return CreateMatrix(cosine, 0.0, sine, 0.0, 1.0, 0.0, -sine, 0.0, cosine);
65 }
66 return CreateMatrix(cosine, -sine, 0.0, sine, cosine, 0.0, 0.0, 0.0, 1.0);
67}
68
69static inline Eigen::Matrix3d RotationMatrix(double angle, int axis)
70{
71 return RotationMatrix(sin(angle), cos(angle), axis);
72}
73
74static inline double EulerAngleFromMatrix(const Eigen::Matrix3d &R, int axis)
75{
76 double t = sqrt(R(0, 0) * R(0, 0) + R(0, 1) * R(0, 1));
77
78 if (t > 16.0 * IK_EPSILON) {
79 if (axis == 0) {
80 return -atan2(R(1, 2), R(2, 2));
81 }
82 if (axis == 1) {
83 return atan2(-R(0, 2), t);
84 }
85 return -atan2(R(0, 1), R(0, 0));
86 }
87
88 if (axis == 0) {
89 return -atan2(-R(2, 1), R(1, 1));
90 }
91 if (axis == 1) {
92 return atan2(-R(0, 2), t);
93 }
94 return 0.0f;
95}
96
97static inline double safe_acos(double f)
98{
99 // acos that does not return NaN with rounding errors
100 if (f <= -1.0) {
101 return M_PI;
102 }
103 if (f >= 1.0) {
104 return 0.0;
105 }
106 return acos(f);
107}
108
109static inline Eigen::Vector3d normalize(const Eigen::Vector3d &v)
110{
111 // a sane normalize function that doesn't give (1, 0, 0) in case
112 // of a zero length vector
113 double len = v.norm();
114 return FuzzyZero(len) ? Eigen::Vector3d(0, 0, 0) : Eigen::Vector3d(v / len);
115}
116
117static inline double angle(const Eigen::Vector3d &v1, const Eigen::Vector3d &v2)
118{
119 return safe_acos(v1.dot(v2));
120}
121
122static inline double ComputeTwist(const Eigen::Matrix3d &R)
123{
124 // qy and qw are the y and w components of the quaternion from R
125 double qy = R(0, 2) - R(2, 0);
126 double qw = R(0, 0) + R(1, 1) + R(2, 2) + 1;
127
128 double tau = 2.0 * atan2(qy, qw);
129
130 return tau;
131}
132
133static inline Eigen::Matrix3d ComputeTwistMatrix(double tau)
134{
135 return RotationMatrix(tau, 1);
136}
137
138static inline void RemoveTwist(Eigen::Matrix3d &R)
139{
140 // compute twist parameter
141 double tau = ComputeTwist(R);
142
143 // compute twist matrix
144 Eigen::Matrix3d T = ComputeTwistMatrix(tau);
145
146 // remove twist
147 R = R * T.transpose();
148}
149
150static inline Eigen::Vector3d SphericalRangeParameters(const Eigen::Matrix3d &R)
151{
152 // compute twist parameter
153 double tau = ComputeTwist(R);
154
155 // compute swing parameters
156 double num = 2.0 * (1.0 + R(1, 1));
157
158 // singularity at pi
159 if (fabs(num) < IK_EPSILON) {
160 // TODO: this does now rotation of size pi over z axis, but could
161 // be any axis, how to deal with this I'm not sure, maybe don't
162 // enforce limits at all then.
163 return Eigen::Vector3d(0.0, tau, 1.0);
164 }
165
166 num = 1.0 / sqrt(num);
167 double ax = -R(2, 1) * num;
168 double az = R(0, 1) * num;
169
170 return Eigen::Vector3d(ax, tau, az);
171}
172
173static inline Eigen::Matrix3d ComputeSwingMatrix(double ax, double az)
174{
175 // length of (ax, 0, az) = sin(theta/2)
176 double sine2 = ax * ax + az * az;
177 double cosine2 = sqrt((sine2 >= 1.0) ? 0.0 : 1.0 - sine2);
178
179 // compute swing matrix
180 Eigen::Matrix3d S(Eigen::Quaterniond(-cosine2, ax, 0.0, az));
181
182 return S;
183}
184
185static inline Eigen::Vector3d MatrixToAxisAngle(const Eigen::Matrix3d &R)
186{
187 Eigen::Vector3d delta = Eigen::Vector3d(R(2, 1) - R(1, 2), R(0, 2) - R(2, 0), R(1, 0) - R(0, 1));
188
189 double c = safe_acos((R(0, 0) + R(1, 1) + R(2, 2) - 1) / 2);
190 double l = delta.norm();
191
192 if (!FuzzyZero(l)) {
193 delta *= c / l;
194 }
195
196 return delta;
197}
198
199static inline bool EllipseClamp(double &ax, double &az, const double *amin, const double *amax)
200{
201 double xlim, zlim, x, z;
202
203 if (ax < 0.0) {
204 x = -ax;
205 xlim = -amin[0];
206 }
207 else {
208 x = ax;
209 xlim = amax[0];
210 }
211
212 if (az < 0.0) {
213 z = -az;
214 zlim = -amin[1];
215 }
216 else {
217 z = az;
218 zlim = amax[1];
219 }
220
221 if (FuzzyZero(xlim) || FuzzyZero(zlim)) {
222 if (x <= xlim && z <= zlim) {
223 return false;
224 }
225
226 x = std::min(x, xlim);
227 z = std::min(z, zlim);
228 }
229 else {
230 double invx = 1.0 / (xlim * xlim);
231 double invz = 1.0 / (zlim * zlim);
232
233 if ((x * x * invx + z * z * invz) <= 1.0) {
234 return false;
235 }
236
237 if (FuzzyZero(x)) {
238 x = 0.0;
239 z = zlim;
240 }
241 else {
242 double rico = z / x;
243 double old_x = x;
244 x = sqrt(1.0 / (invx + invz * rico * rico));
245 if (old_x < 0.0) {
246 x = -x;
247 }
248 z = rico * x;
249 }
250 }
251
252 ax = (ax < 0.0) ? -x : x;
253 az = (az < 0.0) ? -z : z;
254
255 return true;
256}
#define M_PI
ATTR_WARN_UNUSED_RESULT const size_t num
static double EulerAngleFromMatrix(const Eigen::Matrix3d &R, int axis)
Definition IK_Math.h:74
static void RemoveTwist(Eigen::Matrix3d &R)
Definition IK_Math.h:138
static Eigen::Matrix3d CreateMatrix(double xx, double xy, double xz, double yx, double yy, double yz, double zx, double zy, double zz)
Definition IK_Math.h:35
static double angle(const Eigen::Vector3d &v1, const Eigen::Vector3d &v2)
Definition IK_Math.h:117
static Eigen::Vector3d MatrixToAxisAngle(const Eigen::Matrix3d &R)
Definition IK_Math.h:185
static const double IK_EPSILON
Definition IK_Math.h:23
static double ComputeTwist(const Eigen::Matrix3d &R)
Definition IK_Math.h:122
static double safe_acos(double f)
Definition IK_Math.h:97
static double Clamp(const double x, const double min, const double max)
Definition IK_Math.h:30
static Eigen::Matrix3d RotationMatrix(double sine, double cosine, int axis)
Definition IK_Math.h:58
static Eigen::Matrix3d ComputeTwistMatrix(double tau)
Definition IK_Math.h:133
static Eigen::Vector3d SphericalRangeParameters(const Eigen::Matrix3d &R)
Definition IK_Math.h:150
static Eigen::Matrix3d ComputeSwingMatrix(double ax, double az)
Definition IK_Math.h:173
static bool EllipseClamp(double &ax, double &az, const double *amin, const double *amax)
Definition IK_Math.h:199
static bool FuzzyZero(double x)
Definition IK_Math.h:25
ATTR_WARN_UNUSED_RESULT const BMVert * v2
ATTR_WARN_UNUSED_RESULT const BMLoop * l
ATTR_WARN_UNUSED_RESULT const BMVert const BMEdge * e
ATTR_WARN_UNUSED_RESULT const BMVert * v
SIMD_FORCE_INLINE const btScalar & z() const
Return the z value.
Definition btQuadWord.h:117
#define sin
#define cos
VecBase< float, D > normalize(VecOp< float, D >) RET
#define sqrt
#define acos
ccl_device_inline float2 fabs(const float2 a)
ccl_device_inline float3 atan2(const float3 y, const float3 x)
#define M
#define T
#define R
#define min(a, b)
Definition sort.cc:36
max
Definition text_draw.cc:251
uint len
int xy[2]
Definition wm_draw.cc:178