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