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