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 edu.wpi.first.math.MatBuilder; 010import edu.wpi.first.math.Matrix; 011import edu.wpi.first.math.Nat; 012import edu.wpi.first.math.geometry.proto.Transform3dProto; 013import edu.wpi.first.math.geometry.struct.Transform3dStruct; 014import edu.wpi.first.math.jni.Transform3dJNI; 015import edu.wpi.first.math.numbers.N4; 016import edu.wpi.first.units.measure.Distance; 017import edu.wpi.first.util.protobuf.ProtobufSerializable; 018import edu.wpi.first.util.struct.StructSerializable; 019import java.util.Objects; 020 021/** Represents a transformation for a Pose3d in the pose's frame. */ 022public class Transform3d implements ProtobufSerializable, StructSerializable { 023 /** 024 * A preallocated Transform3d representing no transformation. 025 * 026 * <p>This exists to avoid allocations for common transformations. 027 */ 028 public static final Transform3d kZero = new Transform3d(); 029 030 private final Translation3d m_translation; 031 private final Rotation3d m_rotation; 032 033 /** 034 * Constructs the transform that maps the initial pose to the final pose. 035 * 036 * @param initial The initial pose for the transformation. 037 * @param last The final pose for the transformation. 038 */ 039 public Transform3d(Pose3d initial, Pose3d last) { 040 // We are rotating the difference between the translations 041 // using a clockwise rotation matrix. This transforms the global 042 // delta into a local delta (relative to the initial pose). 043 m_translation = 044 last.getTranslation() 045 .minus(initial.getTranslation()) 046 .rotateBy(initial.getRotation().unaryMinus()); 047 048 m_rotation = last.getRotation().minus(initial.getRotation()); 049 } 050 051 /** 052 * Constructs a transform with the given translation and rotation components. 053 * 054 * @param translation Translational component of the transform. 055 * @param rotation Rotational component of the transform. 056 */ 057 public Transform3d(Translation3d translation, Rotation3d rotation) { 058 m_translation = translation; 059 m_rotation = rotation; 060 } 061 062 /** 063 * Constructs a transform with x, y, and z translations instead of a separate Translation3d. 064 * 065 * @param x The x component of the translational component of the transform. 066 * @param y The y component of the translational component of the transform. 067 * @param z The z component of the translational component of the transform. 068 * @param rotation The rotational component of the transform. 069 */ 070 public Transform3d(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 transform with x, y, and z translations instead of a separate Translation3d. The 077 * X, Y, and Z translations will be converted to and tracked as meters. 078 * 079 * @param x The x component of the translational component of the transform. 080 * @param y The y component of the translational component of the transform. 081 * @param z The z component of the translational component of the transform. 082 * @param rotation The rotational component of the transform. 083 */ 084 public Transform3d(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 transform 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 Transform3d(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 /** Constructs the identity transform -- maps an initial pose to itself. */ 106 public Transform3d() { 107 m_translation = Translation3d.kZero; 108 m_rotation = Rotation3d.kZero; 109 } 110 111 /** 112 * Constructs a 3D transform from a 2D transform in the X-Y plane. 113 * 114 * @param transform The 2D transform. 115 * @see Rotation3d#Rotation3d(Rotation2d) 116 * @see Translation3d#Translation3d(Translation2d) 117 */ 118 public Transform3d(Transform2d transform) { 119 m_translation = new Translation3d(transform.getTranslation()); 120 m_rotation = new Rotation3d(transform.getRotation()); 121 } 122 123 /** 124 * Multiplies the transform by the scalar. 125 * 126 * @param scalar The scalar. 127 * @return The scaled Transform3d. 128 */ 129 public Transform3d times(double scalar) { 130 return new Transform3d(m_translation.times(scalar), m_rotation.times(scalar)); 131 } 132 133 /** 134 * Divides the transform by the scalar. 135 * 136 * @param scalar The scalar. 137 * @return The scaled Transform3d. 138 */ 139 public Transform3d div(double scalar) { 140 return times(1.0 / scalar); 141 } 142 143 /** 144 * Composes two transformations. The second transform is applied relative to the orientation of 145 * the first. 146 * 147 * @param other The transform to compose with this one. 148 * @return The composition of the two transformations. 149 */ 150 public Transform3d plus(Transform3d other) { 151 return new Transform3d(Pose3d.kZero, Pose3d.kZero.transformBy(this).transformBy(other)); 152 } 153 154 /** 155 * Returns the translation component of the transformation. 156 * 157 * @return The translational component of the transform. 158 */ 159 public Translation3d getTranslation() { 160 return m_translation; 161 } 162 163 /** 164 * Returns the X component of the transformation's translation. 165 * 166 * @return The x component of the transformation's translation. 167 */ 168 public double getX() { 169 return m_translation.getX(); 170 } 171 172 /** 173 * Returns the Y component of the transformation's translation. 174 * 175 * @return The y component of the transformation's translation. 176 */ 177 public double getY() { 178 return m_translation.getY(); 179 } 180 181 /** 182 * Returns the Z component of the transformation's translation. 183 * 184 * @return The z component of the transformation's translation. 185 */ 186 public double getZ() { 187 return m_translation.getZ(); 188 } 189 190 /** 191 * Returns the X component of the transformation's translation in a measure. 192 * 193 * @return The x component of the transformation's translation in a measure. 194 */ 195 public Distance getMeasureX() { 196 return m_translation.getMeasureX(); 197 } 198 199 /** 200 * Returns the Y component of the transformation's translation in a measure. 201 * 202 * @return The y component of the transformation's translation in a measure. 203 */ 204 public Distance getMeasureY() { 205 return m_translation.getMeasureY(); 206 } 207 208 /** 209 * Returns the Z component of the transformation's translation in a measure. 210 * 211 * @return The z component of the transformation's translation in a measure. 212 */ 213 public Distance getMeasureZ() { 214 return m_translation.getMeasureZ(); 215 } 216 217 /** 218 * Returns an affine transformation matrix representation of this transformation. 219 * 220 * @return An affine transformation matrix representation of this transformation. 221 */ 222 public Matrix<N4, N4> toMatrix() { 223 var vec = m_translation.toVector(); 224 var mat = m_rotation.toMatrix(); 225 return MatBuilder.fill( 226 Nat.N4(), 227 Nat.N4(), 228 mat.get(0, 0), 229 mat.get(0, 1), 230 mat.get(0, 2), 231 vec.get(0), 232 mat.get(1, 0), 233 mat.get(1, 1), 234 mat.get(1, 2), 235 vec.get(1), 236 mat.get(2, 0), 237 mat.get(2, 1), 238 mat.get(2, 2), 239 vec.get(2), 240 0.0, 241 0.0, 242 0.0, 243 1.0); 244 } 245 246 /** 247 * Returns the rotational component of the transformation. 248 * 249 * @return Reference to the rotational component of the transform. 250 */ 251 public Rotation3d getRotation() { 252 return m_rotation; 253 } 254 255 /** 256 * Returns a Twist3d of the current transform (pose delta). If b is the output of {@code a.log()}, 257 * then {@code b.exp()} would yield a. 258 * 259 * @return The twist that maps the current transform. 260 */ 261 public Twist3d log() { 262 var thisQuaternion = m_rotation.getQuaternion(); 263 double[] resultArray = 264 Transform3dJNI.log( 265 this.getX(), 266 this.getY(), 267 this.getZ(), 268 thisQuaternion.getW(), 269 thisQuaternion.getX(), 270 thisQuaternion.getY(), 271 thisQuaternion.getZ()); 272 return new Twist3d( 273 resultArray[0], 274 resultArray[1], 275 resultArray[2], 276 resultArray[3], 277 resultArray[4], 278 resultArray[5]); 279 } 280 281 /** 282 * Invert the transformation. This is useful for undoing a transformation. 283 * 284 * @return The inverted transformation. 285 */ 286 public Transform3d inverse() { 287 // We are rotating the difference between the translations 288 // using a clockwise rotation matrix. This transforms the global 289 // delta into a local delta (relative to the initial pose). 290 return new Transform3d( 291 getTranslation().unaryMinus().rotateBy(getRotation().unaryMinus()), 292 getRotation().unaryMinus()); 293 } 294 295 @Override 296 public String toString() { 297 return String.format("Transform3d(%s, %s)", m_translation, m_rotation); 298 } 299 300 /** 301 * Checks equality between this Transform3d and another object. 302 * 303 * @param obj The other object. 304 * @return Whether the two objects are equal or not. 305 */ 306 @Override 307 public boolean equals(Object obj) { 308 return obj instanceof Transform3d other 309 && other.m_translation.equals(m_translation) 310 && other.m_rotation.equals(m_rotation); 311 } 312 313 @Override 314 public int hashCode() { 315 return Objects.hash(m_translation, m_rotation); 316 } 317 318 /** Transform3d protobuf for serialization. */ 319 public static final Transform3dProto proto = new Transform3dProto(); 320 321 /** Transform3d struct for serialization. */ 322 public static final Transform3dStruct struct = new Transform3dStruct(); 323}