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