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.Meters; 008 009import io.avaje.jsonb.Json; 010import java.util.Collection; 011import java.util.Collections; 012import java.util.Comparator; 013import java.util.Objects; 014import org.wpilib.math.geometry.proto.Translation3dProto; 015import org.wpilib.math.geometry.struct.Translation3dStruct; 016import org.wpilib.math.interpolation.Interpolatable; 017import org.wpilib.math.linalg.VecBuilder; 018import org.wpilib.math.linalg.Vector; 019import org.wpilib.math.numbers.N3; 020import org.wpilib.math.util.MathUtil; 021import org.wpilib.units.measure.Distance; 022import org.wpilib.util.protobuf.ProtobufSerializable; 023import org.wpilib.util.struct.StructSerializable; 024 025/** 026 * Represents a translation in 3D space. This object can be used to represent a point or a vector. 027 * 028 * <p>This assumes that you are using conventional mathematical axes. When the robot is at the 029 * origin facing in the positive X direction, forward is positive X, left is positive Y, and up is 030 * positive Z. 031 */ 032@Json 033public final class Translation3d 034 implements Interpolatable<Translation3d>, ProtobufSerializable, StructSerializable { 035 /** 036 * A preallocated Translation3d representing the origin. 037 * 038 * <p>This exists to avoid allocations for common translations. 039 */ 040 public static final Translation3d kZero = new Translation3d(); 041 042 @Json.Property("x") 043 private final double m_x; 044 045 @Json.Property("y") 046 private final double m_y; 047 048 @Json.Property("z") 049 private final double m_z; 050 051 /** Constructs a Translation3d with X, Y, and Z components equal to zero. */ 052 public Translation3d() { 053 this(0.0, 0.0, 0.0); 054 } 055 056 /** 057 * Constructs a Translation3d with the X, Y, and Z components equal to the provided values. 058 * 059 * @param x The x component of the translation. 060 * @param y The y component of the translation. 061 * @param z The z component of the translation. 062 */ 063 @Json.Creator 064 public Translation3d(double x, double y, double z) { 065 m_x = x; 066 m_y = y; 067 m_z = z; 068 } 069 070 /** 071 * Constructs a Translation3d with the provided distance and angle. This is essentially converting 072 * from polar coordinates to Cartesian coordinates. 073 * 074 * @param distance The distance from the origin to the end of the translation. 075 * @param angle The angle between the x-axis and the translation vector. 076 */ 077 public Translation3d(double distance, Rotation3d angle) { 078 final var rectangular = new Translation3d(distance, 0.0, 0.0).rotateBy(angle); 079 m_x = rectangular.getX(); 080 m_y = rectangular.getY(); 081 m_z = rectangular.getZ(); 082 } 083 084 /** 085 * Constructs a Translation3d with the X, Y, and Z components equal to the provided values. The 086 * components will be converted to and tracked as meters. 087 * 088 * @param x The x component of the translation. 089 * @param y The y component of the translation. 090 * @param z The z component of the translation. 091 */ 092 public Translation3d(Distance x, Distance y, Distance z) { 093 this(x.in(Meters), y.in(Meters), z.in(Meters)); 094 } 095 096 /** 097 * Constructs a 3D translation from a 2D translation in the X-Y plane. 098 * 099 * @param translation The 2D translation. 100 * @see Pose3d#Pose3d(Pose2d) 101 * @see Transform3d#Transform3d(Transform2d) 102 */ 103 public Translation3d(Translation2d translation) { 104 this(translation.getX(), translation.getY(), 0.0); 105 } 106 107 /** 108 * Constructs a Translation3d from a 3D translation vector. The values are assumed to be in 109 * meters. 110 * 111 * @param vector The translation vector. 112 */ 113 public Translation3d(Vector<N3> vector) { 114 this(vector.get(0), vector.get(1), vector.get(2)); 115 } 116 117 /** 118 * Calculates the distance between two translations in 3D space. 119 * 120 * <p>The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²). 121 * 122 * @param other The translation to compute the distance to. 123 * @return The distance between the two translations. 124 */ 125 public double getDistance(Translation3d other) { 126 double dx = other.m_x - m_x; 127 double dy = other.m_y - m_y; 128 double dz = other.m_z - m_z; 129 return Math.sqrt(dx * dx + dy * dy + dz * dz); 130 } 131 132 /** 133 * Calculates the squared distance between two translations in 3D space. This is equivalent to 134 * squaring the result of {@link #getDistance(Translation3d)}, but avoids computing a square root. 135 * 136 * <p>The squared distance between translations is defined as (x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)². 137 * 138 * @param other The translation to compute the squared distance to. 139 * @return The squared distance between the two translations. 140 */ 141 public double getSquaredDistance(Translation3d other) { 142 double dx = other.m_x - m_x; 143 double dy = other.m_y - m_y; 144 double dz = other.m_z - m_z; 145 return dx * dx + dy * dy + dz * dz; 146 } 147 148 /** 149 * Returns the X component of the translation. 150 * 151 * @return The X component of the translation. 152 */ 153 public double getX() { 154 return m_x; 155 } 156 157 /** 158 * Returns the Y component of the translation. 159 * 160 * @return The Y component of the translation. 161 */ 162 public double getY() { 163 return m_y; 164 } 165 166 /** 167 * Returns the Z component of the translation. 168 * 169 * @return The Z component of the translation. 170 */ 171 public double getZ() { 172 return m_z; 173 } 174 175 /** 176 * Returns the X component of the translation in a measure. 177 * 178 * @return The x component of the translation in a measure. 179 */ 180 public Distance getMeasureX() { 181 return Meters.of(m_x); 182 } 183 184 /** 185 * Returns the Y component of the translation in a measure. 186 * 187 * @return The y component of the translation in a measure. 188 */ 189 public Distance getMeasureY() { 190 return Meters.of(m_y); 191 } 192 193 /** 194 * Returns the Z component of the translation in a measure. 195 * 196 * @return The z component of the translation in a measure. 197 */ 198 public Distance getMeasureZ() { 199 return Meters.of(m_z); 200 } 201 202 /** 203 * Returns a 2D translation vector representation of this translation. 204 * 205 * @return A 2D translation vector representation of this translation. 206 */ 207 public Vector<N3> toVector() { 208 return VecBuilder.fill(m_x, m_y, m_z); 209 } 210 211 /** 212 * Returns the norm, or distance from the origin to the translation. 213 * 214 * @return The norm of the translation. 215 */ 216 public double getNorm() { 217 return Math.sqrt(m_x * m_x + m_y * m_y + m_z * m_z); 218 } 219 220 /** 221 * Returns the squared norm, or squared distance from the origin to the translation. This is 222 * equivalent to squaring the result of {@link #getNorm()}, but avoids computing a square root. 223 * 224 * @return The squared norm of the translation. 225 */ 226 public double getSquaredNorm() { 227 return m_x * m_x + m_y * m_y + m_z * m_z; 228 } 229 230 /** 231 * Applies a rotation to the translation in 3D space. 232 * 233 * <p>For example, rotating a Translation3d of <2, 0, 0> by 90 degrees around the Z axis 234 * will return a Translation3d of <0, 2, 0>. 235 * 236 * @param other The rotation to rotate the translation by. 237 * @return The new rotated translation. 238 */ 239 public Translation3d rotateBy(Rotation3d other) { 240 final var p = new Quaternion(0.0, m_x, m_y, m_z); 241 final var qprime = other.getQuaternion().times(p).times(other.getQuaternion().inverse()); 242 return new Translation3d(qprime.getX(), qprime.getY(), qprime.getZ()); 243 } 244 245 /** 246 * Rotates this translation around another translation in 3D space. 247 * 248 * @param other The other translation to rotate around. 249 * @param rot The rotation to rotate the translation by. 250 * @return The new rotated translation. 251 */ 252 public Translation3d rotateAround(Translation3d other, Rotation3d rot) { 253 return this.minus(other).rotateBy(rot).plus(other); 254 } 255 256 /** 257 * Computes the dot product between this translation and another translation in 3D space. 258 * 259 * <p>The dot product between two translations is defined as x₁x₂+y₁y₂+z₁z₂. 260 * 261 * @param other The translation to compute the dot product with. 262 * @return The dot product between the two translations, in square meters. 263 */ 264 public double dot(Translation3d other) { 265 return m_x * other.m_x + m_y * other.m_y + m_z * other.m_z; 266 } 267 268 /** 269 * Computes the cross product between this translation and another translation in 3D space. The 270 * resulting translation will be perpendicular to both translations. 271 * 272 * <p>The 3D cross product between two translations is defined as <y₁z₂-y₂z₁, z₁x₂-z₂x₁, 273 * x₁y₂-x₂y₁>. 274 * 275 * @param other The translation to compute the cross product with. 276 * @return The cross product between the two translations. 277 */ 278 public Vector<N3> cross(Translation3d other) { 279 return VecBuilder.fill( 280 m_y * other.m_z - other.m_y * m_z, 281 m_z * other.m_x - other.m_z * m_x, 282 m_x * other.m_y - other.m_x * m_y); 283 } 284 285 /** 286 * Returns a Translation2d representing this Translation3d projected into the X-Y plane. 287 * 288 * @return A Translation2d representing this Translation3d projected into the X-Y plane. 289 */ 290 public Translation2d toTranslation2d() { 291 return new Translation2d(m_x, m_y); 292 } 293 294 /** 295 * Returns the sum of two translations in 3D space. 296 * 297 * <p>For example, Translation3d(1.0, 2.5, 3.5) + Translation3d(2.0, 5.5, 7.5) = 298 * Translation3d{3.0, 8.0, 11.0). 299 * 300 * @param other The translation to add. 301 * @return The sum of the translations. 302 */ 303 public Translation3d plus(Translation3d other) { 304 return new Translation3d(m_x + other.m_x, m_y + other.m_y, m_z + other.m_z); 305 } 306 307 /** 308 * Returns the difference between two translations. 309 * 310 * <p>For example, Translation3d(5.0, 4.0, 3.0) - Translation3d(1.0, 2.0, 3.0) = 311 * Translation3d(4.0, 2.0, 0.0). 312 * 313 * @param other The translation to subtract. 314 * @return The difference between the two translations. 315 */ 316 public Translation3d minus(Translation3d other) { 317 return new Translation3d(m_x - other.m_x, m_y - other.m_y, m_z - other.m_z); 318 } 319 320 /** 321 * Returns the inverse of the current translation. This is equivalent to negating all components 322 * of the translation. 323 * 324 * @return The inverse of the current translation. 325 */ 326 public Translation3d unaryMinus() { 327 return new Translation3d(-m_x, -m_y, -m_z); 328 } 329 330 /** 331 * Returns the translation multiplied by a scalar. 332 * 333 * <p>For example, Translation3d(2.0, 2.5, 4.5) * 2 = Translation3d(4.0, 5.0, 9.0). 334 * 335 * @param scalar The scalar to multiply by. 336 * @return The scaled translation. 337 */ 338 public Translation3d times(double scalar) { 339 return new Translation3d(m_x * scalar, m_y * scalar, m_z * scalar); 340 } 341 342 /** 343 * Returns the translation divided by a scalar. 344 * 345 * <p>For example, Translation3d(2.0, 2.5, 4.5) / 2 = Translation3d(1.0, 1.25, 2.25). 346 * 347 * @param scalar The scalar to multiply by. 348 * @return The reference to the new mutated object. 349 */ 350 public Translation3d div(double scalar) { 351 return new Translation3d(m_x / scalar, m_y / scalar, m_z / scalar); 352 } 353 354 /** 355 * Returns the nearest Translation3d from a collection of translations. 356 * 357 * @param translations The collection of translations to find the nearest. 358 * @return The nearest Translation3d from the collection. 359 */ 360 public Translation3d nearest(Collection<Translation3d> translations) { 361 return Collections.min(translations, Comparator.comparing(this::getDistance)); 362 } 363 364 @Override 365 public String toString() { 366 return String.format("Translation3d(X: %.2f, Y: %.2f, Z: %.2f)", m_x, m_y, m_z); 367 } 368 369 /** 370 * Checks equality between this Translation3d and another object. 371 * 372 * @param obj The other object. 373 * @return Whether the two objects are equal or not. 374 */ 375 @Override 376 public boolean equals(Object obj) { 377 return obj instanceof Translation3d other 378 && Math.abs(other.m_x - m_x) < 1E-9 379 && Math.abs(other.m_y - m_y) < 1E-9 380 && Math.abs(other.m_z - m_z) < 1E-9; 381 } 382 383 @Override 384 public int hashCode() { 385 return Objects.hash(m_x, m_y, m_z); 386 } 387 388 @Override 389 public Translation3d interpolate(Translation3d endValue, double t) { 390 return new Translation3d( 391 MathUtil.lerp(this.getX(), endValue.getX(), t), 392 MathUtil.lerp(this.getY(), endValue.getY(), t), 393 MathUtil.lerp(this.getZ(), endValue.getZ(), t)); 394 } 395 396 /** Translation3d protobuf for serialization. */ 397 public static final Translation3dProto proto = new Translation3dProto(); 398 399 /** Translation3d struct for serialization. */ 400 public static final Translation3dStruct struct = new Translation3dStruct(); 401}