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