001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package org.wpilib.math.geometry; 006 007import static org.wpilib.units.Units.Radians; 008 009import io.avaje.jsonb.Json; 010import java.util.Objects; 011import org.wpilib.math.geometry.proto.Rotation3dProto; 012import org.wpilib.math.geometry.struct.Rotation3dStruct; 013import org.wpilib.math.interpolation.Interpolatable; 014import org.wpilib.math.linalg.MatBuilder; 015import org.wpilib.math.linalg.Matrix; 016import org.wpilib.math.linalg.VecBuilder; 017import org.wpilib.math.linalg.Vector; 018import org.wpilib.math.numbers.N3; 019import org.wpilib.math.util.MathSharedStore; 020import org.wpilib.math.util.Nat; 021import org.wpilib.units.measure.Angle; 022import org.wpilib.util.protobuf.ProtobufSerializable; 023import org.wpilib.util.struct.StructSerializable; 024 025/** 026 * A rotation in a 3D coordinate frame, represented by a quaternion. Note that unlike 2D rotations, 027 * 3D rotations are not always commutative, so changing the order of rotations changes the result. 028 * 029 * <p>As an example of the order of rotations mattering, suppose we have a card that looks like 030 * this: 031 * 032 * <pre> 033 * ┌───┐ ┌───┐ 034 * │ X │ │ x │ 035 * Front: │ | │ Back: │ · │ 036 * │ | │ │ · │ 037 * └───┘ └───┘ 038 * </pre> 039 * 040 * <p>If we rotate 90º clockwise around the axis into the page, then flip around the left/right 041 * axis, we get one result: 042 * 043 * <pre> 044 * ┌───┐ 045 * │ X │ ┌───────┐ ┌───────┐ 046 * │ | │ → │------X│ → │······x│ 047 * │ | │ └───────┘ └───────┘ 048 * └───┘ 049 * </pre> 050 * 051 * <p>If we flip around the left/right axis, then rotate 90º clockwise around the axis into the 052 * page, we get a different result: 053 * 054 * <pre> 055 * ┌───┐ ┌───┐ 056 * │ X │ │ · │ ┌───────┐ 057 * │ | │ → │ · │ → │x······│ 058 * │ | │ │ x │ └───────┘ 059 * └───┘ └───┘ 060 * </pre> 061 * 062 * <p>Because order matters for 3D rotations, we need to distinguish between <em>extrinsic</em> 063 * rotations and <em>intrinsic</em> rotations. Rotating extrinsically means rotating around the 064 * global axes, while rotating intrinsically means rotating from the perspective of the other 065 * rotation. A neat property is that applying a series of rotations extrinsically is the same as 066 * applying the same series in the opposite order intrinsically. 067 */ 068@Json 069public final class Rotation3d 070 implements Interpolatable<Rotation3d>, ProtobufSerializable, StructSerializable { 071 /** 072 * A preallocated Rotation3d representing no rotation. 073 * 074 * <p>This exists to avoid allocations for common rotations. 075 */ 076 public static final Rotation3d kZero = new Rotation3d(); 077 078 @Json.Property("quaternion") 079 private final Quaternion m_q; 080 081 /** Constructs a Rotation3d representing no rotation. */ 082 public Rotation3d() { 083 m_q = new Quaternion(); 084 } 085 086 /** 087 * Constructs a Rotation3d from a quaternion. 088 * 089 * @param q The quaternion. 090 */ 091 @Json.Creator 092 public Rotation3d(@Json.Alias("quaternion") Quaternion q) { 093 m_q = q.normalize(); 094 } 095 096 /** 097 * Constructs a Rotation3d from extrinsic roll, pitch, and yaw. 098 * 099 * <p>Extrinsic rotations occur in that order around the axes in the fixed global frame rather 100 * than the body frame. 101 * 102 * <p>Angles are measured counterclockwise with the rotation axis pointing "out of the page". If 103 * you point your right thumb along the positive axis direction, your fingers curl in the 104 * direction of positive rotation. 105 * 106 * @param roll The counterclockwise rotation angle around the X axis (roll) in radians. 107 * @param pitch The counterclockwise rotation angle around the Y axis (pitch) in radians. 108 * @param yaw The counterclockwise rotation angle around the Z axis (yaw) in radians. 109 */ 110 public Rotation3d(double roll, double pitch, double yaw) { 111 // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion 112 double cr = Math.cos(roll * 0.5); 113 double sr = Math.sin(roll * 0.5); 114 115 double cp = Math.cos(pitch * 0.5); 116 double sp = Math.sin(pitch * 0.5); 117 118 double cy = Math.cos(yaw * 0.5); 119 double sy = Math.sin(yaw * 0.5); 120 121 m_q = 122 new Quaternion( 123 cr * cp * cy + sr * sp * sy, 124 sr * cp * cy - cr * sp * sy, 125 cr * sp * cy + sr * cp * sy, 126 cr * cp * sy - sr * sp * cy); 127 } 128 129 /** 130 * Constructs a Rotation3d from extrinsic roll, pitch, and yaw. 131 * 132 * <p>Extrinsic rotations occur in that order around the axes in the fixed global frame rather 133 * than the body frame. 134 * 135 * <p>Angles are measured counterclockwise with the rotation axis pointing "out of the page". If 136 * you point your right thumb along the positive axis direction, your fingers curl in the 137 * direction of positive rotation. 138 * 139 * @param roll The counterclockwise rotation angle around the X axis (roll). 140 * @param pitch The counterclockwise rotation angle around the Y axis (pitch). 141 * @param yaw The counterclockwise rotation angle around the Z axis (yaw). 142 */ 143 public Rotation3d(Angle roll, Angle pitch, Angle yaw) { 144 this(roll.in(Radians), pitch.in(Radians), yaw.in(Radians)); 145 } 146 147 /** 148 * Constructs a Rotation3d with the given rotation vector representation. This representation is 149 * equivalent to axis-angle, where the normalized axis is multiplied by the rotation around the 150 * axis in radians. 151 * 152 * @param rvec The rotation vector. 153 */ 154 public Rotation3d(Vector<N3> rvec) { 155 this(rvec, rvec.norm()); 156 } 157 158 /** 159 * Constructs a Rotation3d with the given axis-angle representation. The axis doesn't have to be 160 * normalized. 161 * 162 * @param axis The rotation axis. 163 * @param angleRadians The rotation around the axis in radians. 164 */ 165 public Rotation3d(Vector<N3> axis, double angleRadians) { 166 double norm = axis.norm(); 167 if (norm == 0.0) { 168 m_q = new Quaternion(); 169 return; 170 } 171 172 // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition 173 var v = axis.times(1.0 / norm).times(Math.sin(angleRadians / 2.0)); 174 m_q = new Quaternion(Math.cos(angleRadians / 2.0), v.get(0, 0), v.get(1, 0), v.get(2, 0)); 175 } 176 177 /** 178 * Constructs a Rotation3d with the given axis-angle representation. The axis doesn't have to be 179 * normalized. 180 * 181 * @param axis The rotation axis. 182 * @param angle The rotation around the axis. 183 */ 184 public Rotation3d(Vector<N3> axis, Angle angle) { 185 this(axis, angle.in(Radians)); 186 } 187 188 /** 189 * Constructs a Rotation3d from a rotation matrix. 190 * 191 * @param rotationMatrix The rotation matrix. 192 * @throws IllegalArgumentException if the rotation matrix isn't special orthogonal. 193 */ 194 public Rotation3d(Matrix<N3, N3> rotationMatrix) { 195 final var R = rotationMatrix; 196 197 // Require that the rotation matrix is special orthogonal. This is true if 198 // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1). 199 if (R.times(R.transpose()).minus(Matrix.eye(Nat.N3())).normF() > 1e-9) { 200 var msg = "Rotation matrix isn't orthogonal\n\nR =\n" + R.getStorage().toString() + '\n'; 201 MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace()); 202 throw new IllegalArgumentException(msg); 203 } 204 if (Math.abs(R.det() - 1.0) > 1e-9) { 205 var msg = 206 "Rotation matrix is orthogonal but not special orthogonal\n\nR =\n" 207 + R.getStorage().toString() 208 + '\n'; 209 MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace()); 210 throw new IllegalArgumentException(msg); 211 } 212 213 // Turn rotation matrix into a quaternion 214 // https://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/ 215 double trace = R.get(0, 0) + R.get(1, 1) + R.get(2, 2); 216 double w; 217 double x; 218 double y; 219 double z; 220 221 if (trace > 0.0) { 222 double s = 0.5 / Math.sqrt(trace + 1.0); 223 w = 0.25 / s; 224 x = (R.get(2, 1) - R.get(1, 2)) * s; 225 y = (R.get(0, 2) - R.get(2, 0)) * s; 226 z = (R.get(1, 0) - R.get(0, 1)) * s; 227 } else { 228 if (R.get(0, 0) > R.get(1, 1) && R.get(0, 0) > R.get(2, 2)) { 229 double s = 2.0 * Math.sqrt(1.0 + R.get(0, 0) - R.get(1, 1) - R.get(2, 2)); 230 w = (R.get(2, 1) - R.get(1, 2)) / s; 231 x = 0.25 * s; 232 y = (R.get(0, 1) + R.get(1, 0)) / s; 233 z = (R.get(0, 2) + R.get(2, 0)) / s; 234 } else if (R.get(1, 1) > R.get(2, 2)) { 235 double s = 2.0 * Math.sqrt(1.0 + R.get(1, 1) - R.get(0, 0) - R.get(2, 2)); 236 w = (R.get(0, 2) - R.get(2, 0)) / s; 237 x = (R.get(0, 1) + R.get(1, 0)) / s; 238 y = 0.25 * s; 239 z = (R.get(1, 2) + R.get(2, 1)) / s; 240 } else { 241 double s = 2.0 * Math.sqrt(1.0 + R.get(2, 2) - R.get(0, 0) - R.get(1, 1)); 242 w = (R.get(1, 0) - R.get(0, 1)) / s; 243 x = (R.get(0, 2) + R.get(2, 0)) / s; 244 y = (R.get(1, 2) + R.get(2, 1)) / s; 245 z = 0.25 * s; 246 } 247 } 248 249 m_q = new Quaternion(w, x, y, z); 250 } 251 252 /** 253 * Constructs a Rotation3d that rotates the initial vector onto the final vector. 254 * 255 * <p>This is useful for turning a 3D vector (final) into an orientation relative to a coordinate 256 * system vector (initial). 257 * 258 * @param initial The initial vector. 259 * @param last The final vector. 260 */ 261 public Rotation3d(Vector<N3> initial, Vector<N3> last) { 262 double dot = initial.dot(last); 263 double normProduct = initial.norm() * last.norm(); 264 double dotNorm = dot / normProduct; 265 266 if (dotNorm > 1.0 - 1E-9) { 267 // If the dot product is 1, the two vectors point in the same direction so 268 // there's no rotation. The default initialization of m_q will work. 269 m_q = new Quaternion(); 270 } else if (dotNorm < -1.0 + 1E-9) { 271 // If the dot product is -1, the two vectors are antiparallel, so a 180° 272 // rotation is required. Any other vector can be used to generate an 273 // orthogonal one. 274 275 double x = Math.abs(initial.get(0, 0)); 276 double y = Math.abs(initial.get(1, 0)); 277 double z = Math.abs(initial.get(2, 0)); 278 279 // Find vector that is most orthogonal to initial vector 280 Vector<N3> other; 281 if (x < y) { 282 if (x < z) { 283 // Use x-axis 284 other = VecBuilder.fill(1, 0, 0); 285 } else { 286 // Use z-axis 287 other = VecBuilder.fill(0, 0, 1); 288 } 289 } else { 290 if (y < z) { 291 // Use y-axis 292 other = VecBuilder.fill(0, 1, 0); 293 } else { 294 // Use z-axis 295 other = VecBuilder.fill(0, 0, 1); 296 } 297 } 298 299 var axis = Vector.cross(initial, other); 300 301 double axisNorm = axis.norm(); 302 m_q = 303 new Quaternion( 304 0.0, axis.get(0, 0) / axisNorm, axis.get(1, 0) / axisNorm, axis.get(2, 0) / axisNorm); 305 } else { 306 var axis = Vector.cross(initial, last); 307 308 // https://stackoverflow.com/a/11741520 309 m_q = 310 new Quaternion(normProduct + dot, axis.get(0, 0), axis.get(1, 0), axis.get(2, 0)) 311 .normalize(); 312 } 313 } 314 315 /** 316 * Constructs a 3D rotation from a 2D rotation in the X-Y plane. 317 * 318 * @param rotation The 2D rotation. 319 * @see Pose3d#Pose3d(Pose2d) 320 * @see Transform3d#Transform3d(Transform2d) 321 */ 322 public Rotation3d(Rotation2d rotation) { 323 this(0.0, 0.0, rotation.getRadians()); 324 } 325 326 /** 327 * Takes the inverse of the current rotation. 328 * 329 * @return The inverse of the current rotation. 330 */ 331 public Rotation3d inverse() { 332 return new Rotation3d(m_q.inverse()); 333 } 334 335 /** 336 * Multiplies the current rotation by a scalar. 337 * 338 * @param scalar The scalar. 339 * @return The new scaled Rotation3d. 340 */ 341 public Rotation3d times(double scalar) { 342 return Rotation3d.kZero.interpolate(this, scalar); 343 } 344 345 /** 346 * Divides the current rotation by a scalar. 347 * 348 * @param scalar The scalar. 349 * @return The new scaled Rotation3d. 350 */ 351 public Rotation3d div(double scalar) { 352 return times(1.0 / scalar); 353 } 354 355 /** 356 * Adds the new rotation to the current rotation. The other rotation is applied extrinsically, 357 * which means that it rotates around the global axes. For example, {@code new 358 * Rotation3d(Units.degreesToRadians(90), 0, 0).rotateBy(new Rotation3d(0, 359 * Units.degreesToRadians(45), 0))} rotates by 90 degrees around the +X axis and then by 45 360 * degrees around the global +Y axis. (This is equivalent to {@code new 361 * Rotation3d(Units.degreesToRadians(90), Units.degreesToRadians(45), 0)}) 362 * 363 * @param other The extrinsic rotation to rotate by. 364 * @return The new rotated Rotation3d. 365 */ 366 public Rotation3d rotateBy(Rotation3d other) { 367 return new Rotation3d(other.m_q.times(m_q)); 368 } 369 370 /** 371 * Returns the current rotation relative to the given rotation. Because the result is in the 372 * perspective of the given rotation, it must be applied intrinsically. See the class comment for 373 * definitions of extrinsic and intrinsic rotations. 374 * 375 * @param other The rotation describing the orientation of the new coordinate frame that the 376 * current rotation will be converted into. 377 * @return The current rotation relative to the new orientation of the coordinate frame. 378 */ 379 public Rotation3d relativeTo(Rotation3d other) { 380 // To apply a quaternion intrinsically, we must right-multiply by that quaternion. 381 // Therefore, "this_q relative to other_q" is the q such that other_q q = this_q: 382 // 383 // other_q q = this_q 384 // q = other_q⁻¹ this_q 385 return new Rotation3d(other.m_q.inverse().times(m_q)); 386 } 387 388 /** 389 * Returns the quaternion representation of the Rotation3d. 390 * 391 * @return The quaternion representation of the Rotation3d. 392 */ 393 public Quaternion getQuaternion() { 394 return m_q; 395 } 396 397 /** 398 * Returns the counterclockwise rotation angle around the X axis (roll) in radians. 399 * 400 * @return The counterclockwise rotation angle around the X axis (roll) in radians. 401 */ 402 public double getX() { 403 final var w = m_q.getW(); 404 final var x = m_q.getX(); 405 final var y = m_q.getY(); 406 final var z = m_q.getZ(); 407 408 // wpimath/algorithms.md 409 final var cxcy = 1.0 - 2.0 * (x * x + y * y); 410 final var sxcy = 2.0 * (w * x + y * z); 411 final var cy_sq = cxcy * cxcy + sxcy * sxcy; 412 if (cy_sq > 1e-20) { 413 return Math.atan2(sxcy, cxcy); 414 } else { 415 return 0.0; 416 } 417 } 418 419 /** 420 * Returns the counterclockwise rotation angle around the Y axis (pitch) in radians. 421 * 422 * @return The counterclockwise rotation angle around the Y axis (pitch) in radians. 423 */ 424 public double getY() { 425 final var w = m_q.getW(); 426 final var x = m_q.getX(); 427 final var y = m_q.getY(); 428 final var z = m_q.getZ(); 429 430 // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion 431 double ratio = 2.0 * (w * y - z * x); 432 if (Math.abs(ratio) >= 1.0) { 433 return Math.copySign(Math.PI / 2.0, ratio); 434 } else { 435 return Math.asin(ratio); 436 } 437 } 438 439 /** 440 * Returns the counterclockwise rotation angle around the Z axis (yaw) in radians. 441 * 442 * @return The counterclockwise rotation angle around the Z axis (yaw) in radians. 443 */ 444 public double getZ() { 445 final var w = m_q.getW(); 446 final var x = m_q.getX(); 447 final var y = m_q.getY(); 448 final var z = m_q.getZ(); 449 450 // wpimath/algorithms.md 451 final var cycz = 1.0 - 2.0 * (y * y + z * z); 452 final var cysz = 2.0 * (w * z + x * y); 453 final var cy_sq = cycz * cycz + cysz * cysz; 454 if (cy_sq > 1e-20) { 455 return Math.atan2(cysz, cycz); 456 } else { 457 return Math.atan2(2.0 * w * z, w * w - z * z); 458 } 459 } 460 461 /** 462 * Returns the counterclockwise rotation angle around the X axis (roll) in a measure. 463 * 464 * @return The counterclockwise rotation angle around the x axis (roll) in a measure. 465 */ 466 public Angle getMeasureX() { 467 return Radians.of(getX()); 468 } 469 470 /** 471 * Returns the counterclockwise rotation angle around the Y axis (pitch) in a measure. 472 * 473 * @return The counterclockwise rotation angle around the y axis (pitch) in a measure. 474 */ 475 public Angle getMeasureY() { 476 return Radians.of(getY()); 477 } 478 479 /** 480 * Returns the counterclockwise rotation angle around the Z axis (yaw) in a measure. 481 * 482 * @return The counterclockwise rotation angle around the z axis (yaw) in a measure. 483 */ 484 public Angle getMeasureZ() { 485 return Radians.of(getZ()); 486 } 487 488 /** 489 * Returns the axis in the axis-angle representation of this rotation. 490 * 491 * @return The axis in the axis-angle representation. 492 */ 493 public Vector<N3> getAxis() { 494 double norm = 495 Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ()); 496 if (norm == 0.0) { 497 return VecBuilder.fill(0.0, 0.0, 0.0); 498 } else { 499 return VecBuilder.fill(m_q.getX() / norm, m_q.getY() / norm, m_q.getZ() / norm); 500 } 501 } 502 503 /** 504 * Returns the angle in radians in the axis-angle representation of this rotation. 505 * 506 * @return The angle in radians in the axis-angle representation of this rotation. 507 */ 508 public double getAngle() { 509 double norm = 510 Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ()); 511 return 2.0 * Math.atan2(norm, m_q.getW()); 512 } 513 514 /** 515 * Returns rotation matrix representation of this rotation. 516 * 517 * @return Rotation matrix representation of this rotation. 518 */ 519 public Matrix<N3, N3> toMatrix() { 520 double w = m_q.getW(); 521 double x = m_q.getX(); 522 double y = m_q.getY(); 523 double z = m_q.getZ(); 524 525 // https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation#Quaternion-derived_rotation_matrix 526 return MatBuilder.fill( 527 Nat.N3(), 528 Nat.N3(), 529 1.0 - 2.0 * (y * y + z * z), 530 2.0 * (x * y - w * z), 531 2.0 * (x * z + w * y), 532 2.0 * (x * y + w * z), 533 1.0 - 2.0 * (x * x + z * z), 534 2.0 * (y * z - w * x), 535 2.0 * (x * z - w * y), 536 2.0 * (y * z + w * x), 537 1.0 - 2.0 * (x * x + y * y)); 538 } 539 540 /** 541 * Returns rotation vector representation of this rotation. 542 * 543 * @return Rotation vector representation of this rotation. 544 */ 545 public Vector<N3> toVector() { 546 return m_q.toRotationVector(); 547 } 548 549 /** 550 * Returns the angle in a measure in the axis-angle representation of this rotation. 551 * 552 * @return The angle in a measure in the axis-angle representation of this rotation. 553 */ 554 public Angle getMeasureAngle() { 555 return Radians.of(getAngle()); 556 } 557 558 /** 559 * Returns a Rotation2d representing this Rotation3d projected into the X-Y plane. 560 * 561 * @return A Rotation2d representing this Rotation3d projected into the X-Y plane. 562 */ 563 public Rotation2d toRotation2d() { 564 return new Rotation2d(getZ()); 565 } 566 567 @Override 568 public String toString() { 569 return String.format("Rotation3d(%s)", m_q); 570 } 571 572 /** 573 * Checks equality between this Rotation3d and another object. 574 * 575 * @param obj The other object. 576 * @return Whether the two objects are equal or not. 577 */ 578 @Override 579 public boolean equals(Object obj) { 580 return obj instanceof Rotation3d other 581 && Math.abs(Math.abs(m_q.dot(other.m_q)) - m_q.norm() * other.m_q.norm()) < 1e-9; 582 } 583 584 @Override 585 public int hashCode() { 586 return Objects.hash(m_q); 587 } 588 589 @Override 590 public Rotation3d interpolate(Rotation3d endValue, double t) { 591 // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp 592 // 593 // slerp(q₀, q₁, t) = (q₁q₀⁻¹)ᵗq₀ 594 // 595 // We negate the delta quaternion if necessary to take the shortest path 596 var q0 = m_q; 597 var q1 = endValue.m_q; 598 var delta = q1.times(q0.inverse()); 599 if (delta.getW() < 0.0) { 600 delta = new Quaternion(-delta.getW(), -delta.getX(), -delta.getY(), -delta.getZ()); 601 } 602 return new Rotation3d(delta.pow(t).times(q0)); 603 } 604 605 /** Rotation3d protobuf for serialization. */ 606 public static final Rotation3dProto proto = new Rotation3dProto(); 607 608 /** Rotation3d struct for serialization. */ 609 public static final Rotation3dStruct struct = new Rotation3dStruct(); 610}