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 io.avaje.jsonb.Json; 008import java.util.Objects; 009import org.wpilib.math.geometry.proto.QuaternionProto; 010import org.wpilib.math.geometry.struct.QuaternionStruct; 011import org.wpilib.math.linalg.VecBuilder; 012import org.wpilib.math.linalg.Vector; 013import org.wpilib.math.numbers.N3; 014import org.wpilib.util.protobuf.ProtobufSerializable; 015import org.wpilib.util.struct.StructSerializable; 016 017/** Represents a quaternion. */ 018@Json 019public final class Quaternion implements ProtobufSerializable, StructSerializable { 020 // Scalar r in versor form 021 @Json.Ignore private final double m_w; 022 023 // Vector v in versor form 024 @Json.Ignore private final double m_x; 025 @Json.Ignore private final double m_y; 026 @Json.Ignore private final double m_z; 027 028 /** Constructs a quaternion with a default angle of 0 degrees. */ 029 public Quaternion() { 030 m_w = 1.0; 031 m_x = 0.0; 032 m_y = 0.0; 033 m_z = 0.0; 034 } 035 036 /** 037 * Constructs a quaternion with the given components. 038 * 039 * @param w W component of the quaternion. 040 * @param x X component of the quaternion. 041 * @param y Y component of the quaternion. 042 * @param z Z component of the quaternion. 043 */ 044 @Json.Creator 045 public Quaternion( 046 @Json.Alias("W") double w, 047 @Json.Alias("X") double x, 048 @Json.Alias("Y") double y, 049 @Json.Alias("Z") double z) { 050 m_w = w; 051 m_x = x; 052 m_y = y; 053 m_z = z; 054 } 055 056 /** 057 * Adds another quaternion to this quaternion entrywise. 058 * 059 * @param other The other quaternion. 060 * @return The quaternion sum. 061 */ 062 public Quaternion plus(Quaternion other) { 063 return new Quaternion( 064 getW() + other.getW(), getX() + other.getX(), getY() + other.getY(), getZ() + other.getZ()); 065 } 066 067 /** 068 * Subtracts another quaternion from this quaternion entrywise. 069 * 070 * @param other The other quaternion. 071 * @return The quaternion difference. 072 */ 073 public Quaternion minus(Quaternion other) { 074 return new Quaternion( 075 getW() - other.getW(), getX() - other.getX(), getY() - other.getY(), getZ() - other.getZ()); 076 } 077 078 /** 079 * Divides by a scalar. 080 * 081 * @param scalar The value to scale each component by. 082 * @return The scaled quaternion. 083 */ 084 public Quaternion divide(double scalar) { 085 return new Quaternion(getW() / scalar, getX() / scalar, getY() / scalar, getZ() / scalar); 086 } 087 088 /** 089 * Multiplies with a scalar. 090 * 091 * @param scalar The value to scale each component by. 092 * @return The scaled quaternion. 093 */ 094 public Quaternion times(double scalar) { 095 return new Quaternion(getW() * scalar, getX() * scalar, getY() * scalar, getZ() * scalar); 096 } 097 098 /** 099 * Multiply with another quaternion. 100 * 101 * @param other The other quaternion. 102 * @return The quaternion product. 103 */ 104 public Quaternion times(Quaternion other) { 105 // https://en.wikipedia.org/wiki/Quaternion#Scalar_and_vector_parts 106 final var r1 = m_w; 107 final var r2 = other.m_w; 108 109 // v₁ ⋅ v₂ 110 double dot = m_x * other.m_x + m_y * other.m_y + m_z * other.m_z; 111 112 // v₁ x v₂ 113 double cross_x = m_y * other.m_z - other.m_y * m_z; 114 double cross_y = other.m_x * m_z - m_x * other.m_z; 115 double cross_z = m_x * other.m_y - other.m_x * m_y; 116 117 return new Quaternion( 118 // r = r₁r₂ − v₁ ⋅ v₂ 119 r1 * r2 - dot, 120 // v = r₁v₂ + r₂v₁ + v₁ x v₂ 121 r1 * other.m_x + r2 * m_x + cross_x, 122 r1 * other.m_y + r2 * m_y + cross_y, 123 r1 * other.m_z + r2 * m_z + cross_z); 124 } 125 126 @Override 127 public String toString() { 128 return String.format("Quaternion(%s, %s, %s, %s)", getW(), getX(), getY(), getZ()); 129 } 130 131 /** 132 * Checks equality between this Quaternion and another object. 133 * 134 * @param obj The other object. 135 * @return Whether the two objects are equal or not. 136 */ 137 @Override 138 public boolean equals(Object obj) { 139 return obj instanceof Quaternion other 140 && Math.abs(dot(other) - norm() * other.norm()) < 1e-9 141 && Math.abs(norm() - other.norm()) < 1e-9; 142 } 143 144 @Override 145 public int hashCode() { 146 return Objects.hash(m_w, m_x, m_y, m_z); 147 } 148 149 /** 150 * Returns the conjugate of the quaternion. 151 * 152 * @return The conjugate quaternion. 153 */ 154 public Quaternion conjugate() { 155 return new Quaternion(getW(), -getX(), -getY(), -getZ()); 156 } 157 158 /** 159 * Returns the elementwise product of two quaternions. 160 * 161 * @param other The other quaternion. 162 * @return The dot product of two quaternions. 163 */ 164 public double dot(final Quaternion other) { 165 return getW() * other.getW() 166 + getX() * other.getX() 167 + getY() * other.getY() 168 + getZ() * other.getZ(); 169 } 170 171 /** 172 * Returns the inverse of the quaternion. 173 * 174 * @return The inverse quaternion. 175 */ 176 public Quaternion inverse() { 177 var norm = norm(); 178 return conjugate().divide(norm * norm); 179 } 180 181 /** 182 * Calculates the L2 norm of the quaternion. 183 * 184 * @return The L2 norm. 185 */ 186 public double norm() { 187 return Math.sqrt(dot(this)); 188 } 189 190 /** 191 * Normalizes the quaternion. 192 * 193 * @return The normalized quaternion. 194 */ 195 public Quaternion normalize() { 196 double norm = norm(); 197 if (norm == 0.0) { 198 return new Quaternion(); 199 } else { 200 return new Quaternion(getW() / norm, getX() / norm, getY() / norm, getZ() / norm); 201 } 202 } 203 204 /** 205 * Rational power of a quaternion. 206 * 207 * @param t the power to raise this quaternion to. 208 * @return The quaternion power 209 */ 210 public Quaternion pow(double t) { 211 // q^t = e^(ln(q^t)) = e^(t * ln(q)) 212 return this.log().times(t).exp(); 213 } 214 215 /** 216 * Matrix exponential of a quaternion. 217 * 218 * <p>source: wpimath/algorithms.md 219 * 220 * <p>If this quaternion is in 𝖘𝖔(3) and you are looking for an element of SO(3), use {@link 221 * fromRotationVector} 222 * 223 * @return The Matrix exponential of this quaternion. 224 */ 225 public Quaternion exp() { 226 var scalar = Math.exp(getW()); 227 228 var axial_magnitude = Math.sqrt(getX() * getX() + getY() * getY() + getZ() * getZ()); 229 var cosine = Math.cos(axial_magnitude); 230 231 double axial_scalar; 232 233 if (axial_magnitude < 1e-9) { 234 // Taylor series of sin(θ) / θ near θ = 0: 1 − θ²/6 + θ⁴/120 + O(n⁶) 235 var axial_magnitude_sq = axial_magnitude * axial_magnitude; 236 var axial_magnitude_sq_sq = axial_magnitude_sq * axial_magnitude_sq; 237 axial_scalar = 1.0 - axial_magnitude_sq / 6.0 + axial_magnitude_sq_sq / 120.0; 238 } else { 239 axial_scalar = Math.sin(axial_magnitude) / axial_magnitude; 240 } 241 242 return new Quaternion( 243 cosine * scalar, 244 getX() * axial_scalar * scalar, 245 getY() * axial_scalar * scalar, 246 getZ() * axial_scalar * scalar); 247 } 248 249 /** 250 * The Log operator of a general quaternion. 251 * 252 * <p>source: wpimath/algorithms.md 253 * 254 * <p>If this quaternion is in SO(3) and you are looking for an element of 𝖘𝖔(3), use {@link 255 * toRotationVector} 256 * 257 * @return The logarithm of this quaternion. 258 */ 259 public Quaternion log() { 260 var norm = norm(); 261 var scalar = Math.log(norm); 262 263 var v_norm = Math.sqrt(getX() * getX() + getY() * getY() + getZ() * getZ()); 264 265 var s_norm = getW() / norm; 266 267 if (Math.abs(s_norm + 1) < 1e-9) { 268 return new Quaternion(scalar, -Math.PI, 0, 0); 269 } 270 271 double v_scalar; 272 273 if (v_norm < 1e-9) { 274 // Taylor series expansion of atan2(y/x)/y at y = 0: 275 // 276 // 1/x - 1/3 y²/x³ + O(y⁴) 277 v_scalar = 1.0 / getW() - 1.0 / 3.0 * v_norm * v_norm / (getW() * getW() * getW()); 278 } else { 279 v_scalar = Math.atan2(v_norm, getW()) / v_norm; 280 } 281 282 return new Quaternion(scalar, v_scalar * getX(), v_scalar * getY(), v_scalar * getZ()); 283 } 284 285 /** 286 * Returns W component of the quaternion. 287 * 288 * @return W component of the quaternion. 289 */ 290 @Json.Property(value = "W") 291 public double getW() { 292 return m_w; 293 } 294 295 /** 296 * Returns X component of the quaternion. 297 * 298 * @return X component of the quaternion. 299 */ 300 @Json.Property(value = "X") 301 public double getX() { 302 return m_x; 303 } 304 305 /** 306 * Returns Y component of the quaternion. 307 * 308 * @return Y component of the quaternion. 309 */ 310 @Json.Property(value = "Y") 311 public double getY() { 312 return m_y; 313 } 314 315 /** 316 * Returns Z component of the quaternion. 317 * 318 * @return Z component of the quaternion. 319 */ 320 @Json.Property(value = "Z") 321 public double getZ() { 322 return m_z; 323 } 324 325 /** 326 * Returns the quaternion representation of this rotation vector. 327 * 328 * <p>This is also the exp operator of 𝖘𝖔(3). 329 * 330 * <p>source: wpimath/algorithms.md 331 * 332 * @param rvec The rotation vector. 333 * @return The quaternion representation of this rotation vector. 334 */ 335 public static Quaternion fromRotationVector(Vector<N3> rvec) { 336 double theta = rvec.norm(); 337 338 double cos = Math.cos(theta / 2); 339 340 double axial_scalar; 341 342 if (theta < 1e-9) { 343 // taylor series expansion of sin(θ/2) / θ = 1/2 - θ²/48 + O(θ⁴) 344 axial_scalar = 1.0 / 2.0 - theta * theta / 48.0; 345 } else { 346 axial_scalar = Math.sin(theta / 2) / theta; 347 } 348 349 return new Quaternion( 350 cos, 351 axial_scalar * rvec.get(0, 0), 352 axial_scalar * rvec.get(1, 0), 353 axial_scalar * rvec.get(2, 0)); 354 } 355 356 /** 357 * Returns the rotation vector representation of this quaternion. 358 * 359 * <p>This is also the log operator of SO(3). 360 * 361 * @return The rotation vector representation of this quaternion. 362 */ 363 public Vector<N3> toRotationVector() { 364 // See equation (31) in "Integrating Generic Sensor Fusion Algorithms with 365 // Sound State Representation through Encapsulation of Manifolds" 366 // 367 // https://arxiv.org/pdf/1107.1119.pdf 368 double norm = Math.sqrt(getX() * getX() + getY() * getY() + getZ() * getZ()); 369 370 double coeff; 371 if (norm < 1e-9) { 372 coeff = 2.0 / getW() - 2.0 / 3.0 * norm * norm / (getW() * getW() * getW()); 373 } else { 374 if (getW() < 0.0) { 375 coeff = 2.0 * Math.atan2(-norm, -getW()) / norm; 376 } else { 377 coeff = 2.0 * Math.atan2(norm, getW()) / norm; 378 } 379 } 380 381 return VecBuilder.fill(coeff * getX(), coeff * getY(), coeff * getZ()); 382 } 383 384 /** Quaternion protobuf for serialization. */ 385 public static final QuaternionProto proto = new QuaternionProto(); 386 387 /** Quaternion struct for serialization. */ 388 public static final QuaternionStruct struct = new QuaternionStruct(); 389}