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