Class RotTrlTransform3d

java.lang.Object
org.photonvision.estimation.RotTrlTransform3d

public class RotTrlTransform3d extends Object
Represents a transformation that first rotates a pose around the origin, and then translates it.
  • Constructor Summary

    Constructors
    Constructor
    Description
     
    RotTrlTransform3d(edu.wpi.first.math.geometry.Pose3d initial, edu.wpi.first.math.geometry.Pose3d last)
     
    RotTrlTransform3d(edu.wpi.first.math.geometry.Rotation3d rot, edu.wpi.first.math.geometry.Translation3d trl)
    A rotation-translation transformation.
    RotTrlTransform3d(edu.wpi.first.math.geometry.Transform3d trf)
    Creates a rotation-translation transformation from a Transform3d.
  • Method Summary

    Modifier and Type
    Method
    Description
    edu.wpi.first.math.geometry.Pose3d
    apply(edu.wpi.first.math.geometry.Pose3d pose)
     
    edu.wpi.first.math.geometry.Rotation3d
    apply(edu.wpi.first.math.geometry.Rotation3d rot)
     
    edu.wpi.first.math.geometry.Translation3d
    apply(edu.wpi.first.math.geometry.Translation3d trl)
     
    List<edu.wpi.first.math.geometry.Pose3d>
    applyPoses(List<edu.wpi.first.math.geometry.Pose3d> poses)
     
    List<edu.wpi.first.math.geometry.Rotation3d>
    applyRots(List<edu.wpi.first.math.geometry.Rotation3d> rots)
     
    List<edu.wpi.first.math.geometry.Translation3d>
    applyTrls(List<edu.wpi.first.math.geometry.Translation3d> trls)
     
    edu.wpi.first.math.geometry.Rotation3d
    The rotation component of this transformation
    edu.wpi.first.math.geometry.Transform3d
    This transformation as a Transform3d (as if of the origin)
    edu.wpi.first.math.geometry.Translation3d
    The translation component of this transformation
    The inverse of this transformation.
    makeRelativeTo(edu.wpi.first.math.geometry.Pose3d pose)
    The rotation-translation transformation that makes poses in the world consider this pose as the new origin, or change the basis to this pose.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • RotTrlTransform3d

      public RotTrlTransform3d(edu.wpi.first.math.geometry.Rotation3d rot, edu.wpi.first.math.geometry.Translation3d trl)
      A rotation-translation transformation.

      Applying this RotTrlTransform3d to poses will preserve their current origin-to-pose transform as if the origin was transformed by these components instead.

      Parameters:
      rot - The rotation component
      trl - The translation component
    • RotTrlTransform3d

      public RotTrlTransform3d(edu.wpi.first.math.geometry.Pose3d initial, edu.wpi.first.math.geometry.Pose3d last)
    • RotTrlTransform3d

      public RotTrlTransform3d(edu.wpi.first.math.geometry.Transform3d trf)
      Creates a rotation-translation transformation from a Transform3d.

      Applying this RotTrlTransform3d to poses will preserve their current origin-to-pose transform as if the origin was transformed by trf instead.

      Parameters:
      trf - The origin transformation
    • RotTrlTransform3d

      public RotTrlTransform3d()
  • Method Details

    • makeRelativeTo

      public static RotTrlTransform3d makeRelativeTo(edu.wpi.first.math.geometry.Pose3d pose)
      The rotation-translation transformation that makes poses in the world consider this pose as the new origin, or change the basis to this pose.
      Parameters:
      pose - The new origin
    • inverse

      public RotTrlTransform3d inverse()
      The inverse of this transformation. Applying the inverse will "undo" this transformation.
    • getTransform

      public edu.wpi.first.math.geometry.Transform3d getTransform()
      This transformation as a Transform3d (as if of the origin)
    • getTranslation

      public edu.wpi.first.math.geometry.Translation3d getTranslation()
      The translation component of this transformation
    • getRotation

      public edu.wpi.first.math.geometry.Rotation3d getRotation()
      The rotation component of this transformation
    • apply

      public edu.wpi.first.math.geometry.Translation3d apply(edu.wpi.first.math.geometry.Translation3d trl)
    • applyTrls

      public List<edu.wpi.first.math.geometry.Translation3d> applyTrls(List<edu.wpi.first.math.geometry.Translation3d> trls)
    • apply

      public edu.wpi.first.math.geometry.Rotation3d apply(edu.wpi.first.math.geometry.Rotation3d rot)
    • applyRots

      public List<edu.wpi.first.math.geometry.Rotation3d> applyRots(List<edu.wpi.first.math.geometry.Rotation3d> rots)
    • apply

      public edu.wpi.first.math.geometry.Pose3d apply(edu.wpi.first.math.geometry.Pose3d pose)
    • applyPoses

      public List<edu.wpi.first.math.geometry.Pose3d> applyPoses(List<edu.wpi.first.math.geometry.Pose3d> poses)