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 com.fasterxml.jackson.annotation.JsonAutoDetect; 010import com.fasterxml.jackson.annotation.JsonCreator; 011import com.fasterxml.jackson.annotation.JsonIgnoreProperties; 012import com.fasterxml.jackson.annotation.JsonProperty; 013import java.util.Collection; 014import java.util.Collections; 015import java.util.Comparator; 016import java.util.Objects; 017import org.wpilib.math.geometry.proto.Pose3dProto; 018import org.wpilib.math.geometry.struct.Pose3dStruct; 019import org.wpilib.math.interpolation.Interpolatable; 020import org.wpilib.math.linalg.MatBuilder; 021import org.wpilib.math.linalg.Matrix; 022import org.wpilib.math.numbers.N4; 023import org.wpilib.math.util.Nat; 024import org.wpilib.units.measure.Distance; 025import org.wpilib.util.protobuf.ProtobufSerializable; 026import org.wpilib.util.struct.StructSerializable; 027 028/** Represents a 3D pose containing translational and rotational elements. */ 029@JsonIgnoreProperties(ignoreUnknown = true) 030@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) 031public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, StructSerializable { 032 /** 033 * A preallocated Pose3d representing the origin. 034 * 035 * <p>This exists to avoid allocations for common poses. 036 */ 037 public static final Pose3d kZero = new Pose3d(); 038 039 private final Translation3d m_translation; 040 private final Rotation3d m_rotation; 041 042 /** Constructs a pose at the origin facing toward the positive X axis. */ 043 public Pose3d() { 044 m_translation = Translation3d.kZero; 045 m_rotation = Rotation3d.kZero; 046 } 047 048 /** 049 * Constructs a pose with the specified translation and rotation. 050 * 051 * @param translation The translational component of the pose. 052 * @param rotation The rotational component of the pose. 053 */ 054 @JsonCreator 055 public Pose3d( 056 @JsonProperty(required = true, value = "translation") Translation3d translation, 057 @JsonProperty(required = true, value = "rotation") Rotation3d rotation) { 058 m_translation = translation; 059 m_rotation = rotation; 060 } 061 062 /** 063 * Constructs a pose with x, y, and z translations instead of a separate Translation3d. 064 * 065 * @param x The x component of the translational component of the pose. 066 * @param y The y component of the translational component of the pose. 067 * @param z The z component of the translational component of the pose. 068 * @param rotation The rotational component of the pose. 069 */ 070 public Pose3d(double x, double y, double z, Rotation3d rotation) { 071 m_translation = new Translation3d(x, y, z); 072 m_rotation = rotation; 073 } 074 075 /** 076 * Constructs a pose with x, y, and z translations instead of a separate Translation3d. The X, Y, 077 * and Z translations will be converted to and tracked as meters. 078 * 079 * @param x The x component of the translational component of the pose. 080 * @param y The y component of the translational component of the pose. 081 * @param z The z component of the translational component of the pose. 082 * @param rotation The rotational component of the pose. 083 */ 084 public Pose3d(Distance x, Distance y, Distance z, Rotation3d rotation) { 085 this(x.in(Meters), y.in(Meters), z.in(Meters), rotation); 086 } 087 088 /** 089 * Constructs a pose with the specified affine transformation matrix. 090 * 091 * @param matrix The affine transformation matrix. 092 * @throws IllegalArgumentException if the affine transformation matrix is invalid. 093 */ 094 public Pose3d(Matrix<N4, N4> matrix) { 095 m_translation = new Translation3d(matrix.get(0, 3), matrix.get(1, 3), matrix.get(2, 3)); 096 m_rotation = new Rotation3d(matrix.block(3, 3, 0, 0)); 097 if (matrix.get(3, 0) != 0.0 098 || matrix.get(3, 1) != 0.0 099 || matrix.get(3, 2) != 0.0 100 || matrix.get(3, 3) != 1.0) { 101 throw new IllegalArgumentException("Affine transformation matrix is invalid"); 102 } 103 } 104 105 /** 106 * Constructs a 3D pose from a 2D pose in the X-Y plane. 107 * 108 * @param pose The 2D pose. 109 * @see Rotation3d#Rotation3d(Rotation2d) 110 * @see Translation3d#Translation3d(Translation2d) 111 */ 112 public Pose3d(Pose2d pose) { 113 m_translation = new Translation3d(pose.getX(), pose.getY(), 0.0); 114 m_rotation = new Rotation3d(0.0, 0.0, pose.getRotation().getRadians()); 115 } 116 117 /** 118 * Transforms the pose by the given transformation and returns the new transformed pose. The 119 * transform is applied relative to the pose's frame. Note that this differs from {@link 120 * Pose3d#rotateBy(Rotation3d)}, which is applied relative to the global frame and around the 121 * origin. 122 * 123 * @param other The transform to transform the pose by. 124 * @return The transformed pose. 125 */ 126 public Pose3d plus(Transform3d other) { 127 return transformBy(other); 128 } 129 130 /** 131 * Returns the Transform3d that maps the one pose to another. 132 * 133 * @param other The initial pose of the transformation. 134 * @return The transform that maps the other pose to the current pose. 135 */ 136 public Transform3d minus(Pose3d other) { 137 final var pose = this.relativeTo(other); 138 return new Transform3d(pose.getTranslation(), pose.getRotation()); 139 } 140 141 /** 142 * Returns the translation component of the transformation. 143 * 144 * @return The translational component of the pose. 145 */ 146 @JsonProperty 147 public Translation3d getTranslation() { 148 return m_translation; 149 } 150 151 /** 152 * Returns the X component of the pose's translation. 153 * 154 * @return The x component of the pose's translation. 155 */ 156 public double getX() { 157 return m_translation.getX(); 158 } 159 160 /** 161 * Returns the Y component of the pose's translation. 162 * 163 * @return The y component of the pose's translation. 164 */ 165 public double getY() { 166 return m_translation.getY(); 167 } 168 169 /** 170 * Returns the Z component of the pose's translation. 171 * 172 * @return The z component of the pose's translation. 173 */ 174 public double getZ() { 175 return m_translation.getZ(); 176 } 177 178 /** 179 * Returns the X component of the pose's translation in a measure. 180 * 181 * @return The x component of the pose's translation in a measure. 182 */ 183 public Distance getMeasureX() { 184 return m_translation.getMeasureX(); 185 } 186 187 /** 188 * Returns the Y component of the pose's translation in a measure. 189 * 190 * @return The y component of the pose's translation in a measure. 191 */ 192 public Distance getMeasureY() { 193 return m_translation.getMeasureY(); 194 } 195 196 /** 197 * Returns the Z component of the pose's translation in a measure. 198 * 199 * @return The z component of the pose's translation in a measure. 200 */ 201 public Distance getMeasureZ() { 202 return m_translation.getMeasureZ(); 203 } 204 205 /** 206 * Returns the rotational component of the transformation. 207 * 208 * @return The rotational component of the pose. 209 */ 210 @JsonProperty 211 public Rotation3d getRotation() { 212 return m_rotation; 213 } 214 215 /** 216 * Multiplies the current pose by a scalar. 217 * 218 * @param scalar The scalar. 219 * @return The new scaled Pose3d. 220 */ 221 public Pose3d times(double scalar) { 222 return new Pose3d(m_translation.times(scalar), m_rotation.times(scalar)); 223 } 224 225 /** 226 * Divides the current pose by a scalar. 227 * 228 * @param scalar The scalar. 229 * @return The new scaled Pose3d. 230 */ 231 public Pose3d div(double scalar) { 232 return times(1.0 / scalar); 233 } 234 235 /** 236 * Rotates the pose around the origin and returns the new pose. 237 * 238 * @param other The rotation to transform the pose by, which is applied extrinsically (from the 239 * global frame). 240 * @return The rotated pose. 241 */ 242 public Pose3d rotateBy(Rotation3d other) { 243 return new Pose3d(m_translation.rotateBy(other), m_rotation.rotateBy(other)); 244 } 245 246 /** 247 * Transforms the pose by the given transformation and returns the new transformed pose. The 248 * transform is applied relative to the pose's frame. Note that this differs from {@link 249 * Pose3d#rotateBy(Rotation3d)}, which is applied relative to the global frame and around the 250 * origin. 251 * 252 * @param other The transform to transform the pose by. 253 * @return The transformed pose. 254 */ 255 public Pose3d transformBy(Transform3d other) { 256 // Rotating the transform's rotation by the pose's rotation extrinsically is equivalent to 257 // rotating the pose's rotation by the transform's rotation intrinsically. (We define transforms 258 // as being applied intrinsically.) 259 return new Pose3d( 260 m_translation.plus(other.getTranslation().rotateBy(m_rotation)), 261 other.getRotation().rotateBy(m_rotation)); 262 } 263 264 /** 265 * Returns the current pose relative to the given pose. 266 * 267 * <p>This function can often be used for trajectory tracking or pose stabilization algorithms to 268 * get the error between the reference and the current pose. 269 * 270 * @param other The pose that is the origin of the new coordinate frame that the current pose will 271 * be converted into. 272 * @return The current pose relative to the new origin pose. 273 */ 274 public Pose3d relativeTo(Pose3d other) { 275 var transform = new Transform3d(other, this); 276 return new Pose3d(transform.getTranslation(), transform.getRotation()); 277 } 278 279 /** 280 * Rotates the current pose around a point in 3D space. 281 * 282 * @param point The point in 3D space to rotate around. 283 * @param rot The rotation to rotate the pose by. 284 * @return The new rotated pose. 285 */ 286 public Pose3d rotateAround(Translation3d point, Rotation3d rot) { 287 return new Pose3d(m_translation.rotateAround(point, rot), m_rotation.rotateBy(rot)); 288 } 289 290 /** 291 * Returns an affine transformation matrix representation of this pose. 292 * 293 * @return An affine transformation matrix representation of this pose. 294 */ 295 public Matrix<N4, N4> toMatrix() { 296 var vec = m_translation.toVector(); 297 var mat = m_rotation.toMatrix(); 298 return MatBuilder.fill( 299 Nat.N4(), 300 Nat.N4(), 301 mat.get(0, 0), 302 mat.get(0, 1), 303 mat.get(0, 2), 304 vec.get(0), 305 mat.get(1, 0), 306 mat.get(1, 1), 307 mat.get(1, 2), 308 vec.get(1), 309 mat.get(2, 0), 310 mat.get(2, 1), 311 mat.get(2, 2), 312 vec.get(2), 313 0.0, 314 0.0, 315 0.0, 316 1.0); 317 } 318 319 /** 320 * Returns a Pose2d representing this Pose3d projected into the X-Y plane. 321 * 322 * @return A Pose2d representing this Pose3d projected into the X-Y plane. 323 */ 324 public Pose2d toPose2d() { 325 return new Pose2d(m_translation.toTranslation2d(), m_rotation.toRotation2d()); 326 } 327 328 /** 329 * Returns the nearest Pose3d from a collection of poses. If two or more poses in the collection 330 * have the same distance from this pose, return the one with the closest rotation component. 331 * 332 * @param poses The collection of poses to find the nearest. 333 * @return The nearest Pose3d from the collection. 334 */ 335 public Pose3d nearest(Collection<Pose3d> poses) { 336 return Collections.min( 337 poses, 338 Comparator.comparing( 339 (Pose3d other) -> this.getTranslation().getDistance(other.getTranslation())) 340 .thenComparing( 341 (Pose3d other) -> this.getRotation().relativeTo(other.getRotation()).getAngle())); 342 } 343 344 @Override 345 public String toString() { 346 return String.format("Pose3d(%s, %s)", m_translation, m_rotation); 347 } 348 349 /** 350 * Checks equality between this Pose3d and another object. 351 * 352 * @param obj The other object. 353 * @return Whether the two objects are equal or not. 354 */ 355 @Override 356 public boolean equals(Object obj) { 357 return obj instanceof Pose3d pose 358 && m_translation.equals(pose.m_translation) 359 && m_rotation.equals(pose.m_rotation); 360 } 361 362 @Override 363 public int hashCode() { 364 return Objects.hash(m_translation, m_rotation); 365 } 366 367 @Override 368 public Pose3d interpolate(Pose3d endValue, double t) { 369 if (t < 0) { 370 return this; 371 } else if (t >= 1) { 372 return endValue; 373 } else { 374 var twist = endValue.minus(this).log(); 375 var scaledTwist = 376 new Twist3d( 377 twist.dx * t, twist.dy * t, twist.dz * t, twist.rx * t, twist.ry * t, twist.rz * t); 378 return this.plus(scaledTwist.exp()); 379 } 380 } 381 382 /** Pose3d protobuf for serialization. */ 383 public static final Pose3dProto proto = new Pose3dProto(); 384 385 /** Pose3d struct for serialization. */ 386 public static final Pose3dStruct struct = new Pose3dStruct(); 387}