Class CoordinateTransformation

java.lang.Object
com.irurueta.navigation.frames.CoordinateTransformation
All Implemented Interfaces:
Serializable, Cloneable

public class CoordinateTransformation extends Object implements Serializable, Cloneable
Contains a coordinate transformation matrix, or rotation matrix. The coordinate transformation matrix is a 3x3 matrix where a vector may be transformed in one step from one set of resolving axes to another by pre-multiplying it by the appropriate coordinate transformation matrix. The coordinate transformation matrix is associated to a source and destination frame. This implementation is based on the equations defined in "Principles of GNSS, Inertial, and Multi-sensor Integrated Navigation Systems, Second Edition" and on the companion software available at: https://github.com/ymjdz/MATLAB-Codes/blob/master/Euler_to_CTM.m https://github.com/ymjdz/MATLAB-Codes/blob/master/CTM_to_Euler.m
See Also:
  • Field Details

    • ROWS

      public static final int ROWS
      Number of rows of a coordinate transformation matrix.
      See Also:
    • COLS

      public static final int COLS
      Number of columns of a coordinate transformation matrix.
      See Also:
    • DEFAULT_THRESHOLD

      public static final double DEFAULT_THRESHOLD
      Default threshold to consider a matrix valid.
      See Also:
    • EARTH_ROTATION_RATE

      public static final double EARTH_ROTATION_RATE
      Earth rotation rate expressed in radians per second (rad/s).
      See Also:
    • matrix

      com.irurueta.algebra.Matrix matrix
      3x3 matrix containing a rotation.
    • sourceType

      private FrameType sourceType
      Source frame type.
    • destinationType

      private FrameType destinationType
      Destination frame type.
  • Constructor Details

    • CoordinateTransformation

      public CoordinateTransformation(FrameType sourceType, FrameType destinationType)
      Constructor. Initializes rotation as the identity (no rotation).
      Parameters:
      sourceType - source frame type.
      destinationType - destination frame type.
      Throws:
      NullPointerException - if either source or destination frame types are null.
    • CoordinateTransformation

      public CoordinateTransformation(com.irurueta.algebra.Matrix matrix, FrameType sourceType, FrameType destinationType, double threshold) throws com.irurueta.geometry.InvalidRotationMatrixException
      Constructor.
      Parameters:
      matrix - a 3x3 matrix containing a rotation.
      sourceType - source frame type.
      destinationType - destination frame type.
      threshold - threshold to validate rotation matrix.
      Throws:
      com.irurueta.geometry.InvalidRotationMatrixException - if provided matrix is not a valid rotation matrix (3x3 and orthonormal).
      NullPointerException - if either source or destination frame types are null.
      IllegalArgumentException - if provided threshold is negative.
    • CoordinateTransformation

      public CoordinateTransformation(com.irurueta.algebra.Matrix matrix, FrameType sourceType, FrameType destinationType) throws com.irurueta.geometry.InvalidRotationMatrixException
      Constructor.
      Parameters:
      matrix - a 3x3 matrix containing a rotation.
      sourceType - source frame type.
      destinationType - destination frame type.
      Throws:
      com.irurueta.geometry.InvalidRotationMatrixException - if provided matrix is not a valid rotation matrix (3x3 and orthonormal).
      NullPointerException - if either source or destination frame types are null.
    • CoordinateTransformation

      public CoordinateTransformation(double roll, double pitch, double yaw, FrameType sourceType, FrameType destinationType)
      Constructor with Euler angles. Notice that these angles do not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      roll - roll Euler angle (around x-axis) expressed in radians.
      pitch - pitch Euler angle (around y-axis) expressed in radians.
      yaw - yaw Euler angle (around z-axis) expressed in radians.
      sourceType - source frame type.
      destinationType - destination frame type.
    • CoordinateTransformation

      public CoordinateTransformation(com.irurueta.units.Angle roll, com.irurueta.units.Angle pitch, com.irurueta.units.Angle yaw, FrameType sourceType, FrameType destinationType)
      Constructor with Euler angles. Notice that these angles do not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      roll - roll Euler angle (around x-axis).
      pitch - pitch Euler angle (around y-axis).
      yaw - yaw Euler angle (around z-axis).
      sourceType - source frame type.
      destinationType - destination frame type.
    • CoordinateTransformation

      public CoordinateTransformation(com.irurueta.geometry.Rotation3D rotation, FrameType sourceType, FrameType destinationType)
      Constructor with 3D rotation.
      Parameters:
      rotation - 3D rotation.
      sourceType - source frame type.
      destinationType - destination frame type.
    • CoordinateTransformation

      public CoordinateTransformation(CoordinateTransformation input)
      Constructor.
      Parameters:
      input - other coordinate transformation matrix to copy data from.
  • Method Details

    • getMatrix

      public com.irurueta.algebra.Matrix getMatrix()
      Gets matrix containing a rotation.
      Returns:
      3x3 matrix containing a rotation.
    • getMatrix

      public void getMatrix(com.irurueta.algebra.Matrix result)
      Gets matrix containing a rotation.
      Parameters:
      result - instance where internal 3x3 matrix containing a rotation will be copied to.
    • setMatrix

      public void setMatrix(com.irurueta.algebra.Matrix matrix, double threshold) throws com.irurueta.geometry.InvalidRotationMatrixException
      Sets matrix containing a rotation.
      Parameters:
      matrix - a 3x3 matrix containing a rotation.
      threshold - threshold to validate rotation matrix.
      Throws:
      com.irurueta.geometry.InvalidRotationMatrixException - if provided matrix is not a valid rotation matrix (3x3 and orthonormal).
      IllegalArgumentException - if provided threshold is negative.
    • setMatrix

      public void setMatrix(com.irurueta.algebra.Matrix matrix) throws com.irurueta.geometry.InvalidRotationMatrixException
      Sets matrix containing a rotation.
      Parameters:
      matrix - a 3x3 matrix containing a rotation.
      Throws:
      com.irurueta.geometry.InvalidRotationMatrixException - if provided matrix is not a valid rotation matrix (3x3 and orthonormal).
    • isValidMatrix

      public static boolean isValidMatrix(com.irurueta.algebra.Matrix matrix, double threshold)
      Determines whether provided matrix is a valid rotation matrix (3x3 and orthonormal) up to provided threshold.
      Parameters:
      matrix - matrix to be checked.
      threshold - threshold to determine whether matrix is valid.
      Returns:
      true if matrix is valid, false otherwise.
      Throws:
      IllegalArgumentException - if provided threshold value is negative.
    • isValidMatrix

      public static boolean isValidMatrix(com.irurueta.algebra.Matrix matrix)
      Determines whether provided matrix is a valid rotation matrix (3x3 and orthonormal) up to default threshold DEFAULT_THRESHOLD.
      Parameters:
      matrix - matrix to be checked.
      Returns:
      true if matrix is valid, false otherwise.
    • getRollEulerAngle

      public double getRollEulerAngle()
      Gets roll Euler angle (around x-axis) expressed in radians. Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Returns:
      roll Euler angle.
    • getRollEulerAngleMeasurement

      public void getRollEulerAngleMeasurement(com.irurueta.units.Angle result)
      Gets roll Euler angle (around x-axis). Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      result - instance where roll Euler angle will be stored.
    • getRollEulerAngleMeasurement

      public com.irurueta.units.Angle getRollEulerAngleMeasurement()
      Gets roll Euler angle (around x-axis). Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Returns:
      roll Euler angle.
    • getPitchEulerAngle

      public double getPitchEulerAngle()
      Gets pitch Euler angle (around y-axis) expressed in radians. Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Returns:
      pitch Euler angle.
    • getPitchEulerAngleMeasurement

      public void getPitchEulerAngleMeasurement(com.irurueta.units.Angle result)
      Gets pitch Euler angle (around y-axis). Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      result - instance where pitch Euler angle will be stored.
    • getPitchEulerAngleMeasurement

      public com.irurueta.units.Angle getPitchEulerAngleMeasurement()
      Gets pitch Euler angle (around y-axis). Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Returns:
      pitch Euler angle.
    • getYawEulerAngle

      public double getYawEulerAngle()
      Gets yaw Euler angle (around z-axis) expressed in radians. Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Returns:
      yaw Euler angle.
    • getYawEulerAngleMeasurement

      public void getYawEulerAngleMeasurement(com.irurueta.units.Angle result)
      Gets yaw Euler angle (around z-axis). Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      result - instance where yaw Euler angle will be stored.
    • getYawEulerAngleMeasurement

      public com.irurueta.units.Angle getYawEulerAngleMeasurement()
      Gets yaw Euler angle (around z-axis). Notice that this angle does not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Returns:
      yaw Euler angle.
    • setEulerAngles

      public void setEulerAngles(double roll, double pitch, double yaw)
      Sets euler angles (roll, pitch and yaw) expressed in radians. Notice that these angles do not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      roll - roll Euler angle (around x-axis) expressed in radians.
      pitch - pitch Euler angle (around y-axis) expressed in radians.
      yaw - yaw Euler angle (around z-axis) expressed in radians.
    • setEulerAngles

      public void setEulerAngles(com.irurueta.units.Angle roll, com.irurueta.units.Angle pitch, com.irurueta.units.Angle yaw)
      Sets euler angles (roll, pitch and yaw). Notice that these angles do not match angles obtained from Rotation3D or Quaternion because they are referred to different axes.
      Parameters:
      roll - roll Euler angle (around x-axis).
      pitch - pitch Euler angle (around y-axis).
      yaw - yaw Euler angle (around z-axis).
    • getSourceType

      public FrameType getSourceType()
      Gets source frame type.
      Returns:
      source frame type.
    • setSourceType

      public void setSourceType(FrameType sourceType)
      Sets source frame type.
      Parameters:
      sourceType - source frame type.
      Throws:
      NullPointerException - if provided value is null.
    • getDestinationType

      public FrameType getDestinationType()
      Gets destination frame type.
      Returns:
      destination frame type.
    • setDestinationType

      public void setDestinationType(FrameType destinationType)
      Sets destination frame type.
      Parameters:
      destinationType - destination frame type.
      Throws:
      NullPointerException - if provided value is null.
    • asRotation

      public com.irurueta.geometry.Rotation3D asRotation() throws com.irurueta.geometry.InvalidRotationMatrixException
      Gets internal matrix as a 3D rotation.
      Returns:
      a 3D rotation representing the internal matrix.
      Throws:
      com.irurueta.geometry.InvalidRotationMatrixException - if internal matrix cannot be converted to a 3D rotation.
    • asRotation

      public void asRotation(com.irurueta.geometry.Rotation3D result) throws com.irurueta.geometry.InvalidRotationMatrixException
      Gets internal matrix as a 3D rotation.
      Parameters:
      result - instance where 3D rotation will be stored.
      Throws:
      com.irurueta.geometry.InvalidRotationMatrixException - if internal matrix cannot be converted to a 3D rotation.
    • fromRotation

      public void fromRotation(com.irurueta.geometry.Rotation3D rotation)
      Sets internal matrix as the inhomogeneous matrix representation of provided 3D rotation.
      Parameters:
      rotation - 3D rotation to set matrix from.
    • copyTo

      public void copyTo(CoordinateTransformation output)
      Copies this instance data into provided instance.
      Parameters:
      output - destination instance where data will be copied to.
    • copyFrom

      public void copyFrom(CoordinateTransformation input)
      Copies data of provided instance into this instance.
      Parameters:
      input - instance to copy data from.
    • hashCode

      public int hashCode()
      Computes and returns hash code for this instance. Hash codes are almost unique values that are useful for fast classification and storage of objects in collections.
      Overrides:
      hashCode in class Object
      Returns:
      Hash code.
    • equals

      public boolean equals(Object obj)
      Checks if provided object is a CoordinateTransformationMatrix having exactly the same contents as this instance.
      Overrides:
      equals in class Object
      Parameters:
      obj - Object to be compared.
      Returns:
      true if both objects are considered to be equal, false otherwise.
    • equals

      public boolean equals(CoordinateTransformation other)
      Checks if provided instance has exactly the same contents as this instance.
      Parameters:
      other - instance to be compared.
      Returns:
      true if both instances are considered to be equal, false otherwise.
    • equals

      public boolean equals(CoordinateTransformation other, double threshold)
      Checks if provided instance has contents similar to this instance up to provided threshold value.
      Parameters:
      other - instance to be compared.
      threshold - maximum difference allowed between values on internal matrix.
      Returns:
      true if both instances are considered to be equal (up to provided threshold), false otherwise.
    • inverse

      public void inverse(CoordinateTransformation result)
      Computes the inverse of this coordinate transformation matrix and stores the result into provided instance.
      Parameters:
      result - instance where inverse will be stored.
    • inverse

      public void inverse()
      Converts this instance into its inverse coordinate transformation matrix.
    • inverseAndReturnNew

      public CoordinateTransformation inverseAndReturnNew()
      Computes the inverse of this coordinate transformation matrix and returns it as a new instance.
      Returns:
      the inverse of this coordinate transformation matrix.
    • ecefToNedMatrix

      public static void ecefToNedMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude, com.irurueta.algebra.Matrix result)
      Computes matrix to convert ECEF to NED coordinates.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      result - instance where computed matrix will be stored.
    • ecefToNedMatrix

      public static com.irurueta.algebra.Matrix ecefToNedMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude)
      Computes matrix to convert ECEF to NED coordinates.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      Returns:
      a new matrix to convert ECEF to NED coordinates.
    • ecefToNedMatrix

      public static void ecefToNedMatrix(double latitude, double longitude, com.irurueta.algebra.Matrix result)
      Computes matrix to convert ECEF to NED coordinates.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      result - instance where computed matrix will be stored.
    • ecefToNedMatrix

      public static com.irurueta.algebra.Matrix ecefToNedMatrix(double latitude, double longitude)
      Computes matrix to convert ECEF to NED coordinates.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      Returns:
      a new matrix to convert ECEF to NED coordinates.
    • ecefToNedCoordinateTransformationMatrix

      public static void ecefToNedCoordinateTransformationMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude, CoordinateTransformation result)
      Computes ECEF to NED coordinate transformation matrix.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      result - instance where result will be stored.
    • ecefToNedCoordinateTransformationMatrix

      public static CoordinateTransformation ecefToNedCoordinateTransformationMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude)
      Computes ECEF to NED coordinate transformation matrix.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      Returns:
      a new ECEF to NED coordinate transformation matrix.
    • ecefToNedCoordinateTransformationMatrix

      public static void ecefToNedCoordinateTransformationMatrix(double latitude, double longitude, CoordinateTransformation result)
      Computes ECEF to NED coordinate transformation matrix.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      result - instance where result will be stored.
    • ecefToNedCoordinateTransformationMatrix

      public static CoordinateTransformation ecefToNedCoordinateTransformationMatrix(double latitude, double longitude)
      Computes ECEF to NED coordinate transformation matrix.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      Returns:
      a new ECEF to NED coordinate transformation matrix.
    • nedToEcefMatrix

      public static void nedToEcefMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude, com.irurueta.algebra.Matrix result)
      Computes matrix to convert NED to ECEF coordinates.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      result - instance where computed matrix will be stored.
    • nedToEcefMatrix

      public static com.irurueta.algebra.Matrix nedToEcefMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude)
      Computes matrix to convert NED to ECEF coordinates.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      Returns:
      a new matrix to convert NED to ECEF coordinates.
    • nedToEcefMatrix

      public static void nedToEcefMatrix(double latitude, double longitude, com.irurueta.algebra.Matrix result)
      Computes matrix to convert NED to ECEF coordinates.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      result - instance where computed matrix will be stored.
    • nedToEcefMatrix

      public static com.irurueta.algebra.Matrix nedToEcefMatrix(double latitude, double longitude)
      Computes matrix to convert NED to ECEF coordinates.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      Returns:
      a new matrix to convert NED to ECEF coordinates.
    • nedToEcefCoordinateTransformationMatrix

      public static void nedToEcefCoordinateTransformationMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude, CoordinateTransformation result)
      Computes NED to ECEF coordinate transformation matrix.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      result - instance where result will be stored.
    • nedToEcefCoordinateTransformationMatrix

      public static CoordinateTransformation nedToEcefCoordinateTransformationMatrix(com.irurueta.units.Angle latitude, com.irurueta.units.Angle longitude)
      Computes NED to ECEF coordinate transformation matrix.
      Parameters:
      latitude - latitude angle.
      longitude - longitude angle.
      Returns:
      a new NED to ECEF coordinate transformation matrix.
    • nedToEcefCoordinateTransformationMatrix

      public static void nedToEcefCoordinateTransformationMatrix(double latitude, double longitude, CoordinateTransformation result)
      Computes NED to ECEF coordinate transformation matrix.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      result - instance where result will be stored.
    • nedToEcefCoordinateTransformationMatrix

      public static CoordinateTransformation nedToEcefCoordinateTransformationMatrix(double latitude, double longitude)
      Computes NED to ECEF coordinate transformation matrix.
      Parameters:
      latitude - latitude expressed in radians.
      longitude - longitude expressed in radians.
      Returns:
      a new NED to ECEF coordinate transformation matrix.
    • ecefToEciMatrixFromTimeInterval

      public static void ecefToEciMatrixFromTimeInterval(com.irurueta.units.Time timeInterval, com.irurueta.algebra.Matrix result)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      result - instance where result will be stored.
    • ecefToEciMatrixFromTimeInterval

      public static void ecefToEciMatrixFromTimeInterval(double timeInterval, com.irurueta.algebra.Matrix result)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      result - instance where result will be stored.
    • ecefToEciMatrixFromAngle

      public static void ecefToEciMatrixFromAngle(com.irurueta.units.Angle angle, com.irurueta.algebra.Matrix result)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      result - instance where result will be stored.
    • ecefToEciMatrixFromAngle

      public static void ecefToEciMatrixFromAngle(double angle, com.irurueta.algebra.Matrix result)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      result - instance where result will be stored.
    • ecefToEciMatrixFromTimeInterval

      public static com.irurueta.algebra.Matrix ecefToEciMatrixFromTimeInterval(com.irurueta.units.Time timeInterval)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciMatrixFromTimeInterval

      public static com.irurueta.algebra.Matrix ecefToEciMatrixFromTimeInterval(double timeInterval)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciMatrixFromAngle

      public static com.irurueta.algebra.Matrix ecefToEciMatrixFromAngle(com.irurueta.units.Angle angle)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciMatrixFromAngle

      public static com.irurueta.algebra.Matrix ecefToEciMatrixFromAngle(double angle)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciCoordinateTransformationMatrixFromTimeInterval

      public static void ecefToEciCoordinateTransformationMatrixFromTimeInterval(com.irurueta.units.Time timeInterval, CoordinateTransformation result)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      result - instance where result will be stored.
    • ecefToEciCoordinateTransformationMatrixFromTimeInterval

      public static void ecefToEciCoordinateTransformationMatrixFromTimeInterval(double timeInterval, CoordinateTransformation result)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      result - instance where result will be stored.
    • ecefToEciCoordinateTransformationMatrixFromAngle

      public static void ecefToEciCoordinateTransformationMatrixFromAngle(com.irurueta.units.Angle angle, CoordinateTransformation result)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      result - instance where result will be stored.
    • ecefToEciCoordinateTransformationMatrixFromAngle

      public static void ecefToEciCoordinateTransformationMatrixFromAngle(double angle, CoordinateTransformation result)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      result - instance where result will be stored.
    • ecefToEciCoordinateTransformationMatrixFromTimeInterval

      public static CoordinateTransformation ecefToEciCoordinateTransformationMatrixFromTimeInterval(com.irurueta.units.Time timeInterval)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciCoordinateTransformationMatrixFromTimeInterval

      public static CoordinateTransformation ecefToEciCoordinateTransformationMatrixFromTimeInterval(double timeInterval)
      Computes ECEF to ECI coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciCoordinateTransformationMatrixFromAngle

      public static CoordinateTransformation ecefToEciCoordinateTransformationMatrixFromAngle(com.irurueta.units.Angle angle)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • ecefToEciCoordinateTransformationMatrixFromAngle

      public static CoordinateTransformation ecefToEciCoordinateTransformationMatrixFromAngle(double angle)
      Computes ECEF to ECI coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      Returns:
      a new ECEF to ECI coordinate transformation matrix.
    • eciToEcefMatrixFromTimeInterval

      public static void eciToEcefMatrixFromTimeInterval(com.irurueta.units.Time timeInterval, com.irurueta.algebra.Matrix result)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      result - instance where result will be stored.
    • eciToEcefMatrixFromTimeInterval

      public static void eciToEcefMatrixFromTimeInterval(double timeInterval, com.irurueta.algebra.Matrix result)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      result - instance where result will be stored.
    • eciToEcefMatrixFromAngle

      public static void eciToEcefMatrixFromAngle(com.irurueta.units.Angle angle, com.irurueta.algebra.Matrix result)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      result - instance where result will be stored.
    • eciToEcefMatrixFromAngle

      public static void eciToEcefMatrixFromAngle(double angle, com.irurueta.algebra.Matrix result)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      result - instance where result will be stored.
    • eciToEcefMatrixFromTimeInterval

      public static com.irurueta.algebra.Matrix eciToEcefMatrixFromTimeInterval(com.irurueta.units.Time timeInterval)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefMatrixFromTimeInterval

      public static com.irurueta.algebra.Matrix eciToEcefMatrixFromTimeInterval(double timeInterval)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefMatrixFromAngle

      public static com.irurueta.algebra.Matrix eciToEcefMatrixFromAngle(com.irurueta.units.Angle angle)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefMatrixFromAngle

      public static com.irurueta.algebra.Matrix eciToEcefMatrixFromAngle(double angle)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefCoordinateTransformationMatrixFromTimeInterval

      public static void eciToEcefCoordinateTransformationMatrixFromTimeInterval(com.irurueta.units.Time timeInterval, CoordinateTransformation result)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      result - instance where result will be stored.
    • eciToEcefCoordinateTransformationMatrixFromTimeInterval

      public static void eciToEcefCoordinateTransformationMatrixFromTimeInterval(double timeInterval, CoordinateTransformation result)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      result - instance where result will be stored.
    • eciToEcefCoordinateTransformationMatrixFromAngle

      public static void eciToEcefCoordinateTransformationMatrixFromAngle(com.irurueta.units.Angle angle, CoordinateTransformation result)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      result - instance where result will be stored.
    • eciToEcefCoordinateTransformationMatrixFromAngle

      public static void eciToEcefCoordinateTransformationMatrixFromAngle(double angle, CoordinateTransformation result)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      result - instance where result will be stored.
    • eciToEcefCoordinateTransformationMatrixFromTimeInterval

      public static CoordinateTransformation eciToEcefCoordinateTransformationMatrixFromTimeInterval(com.irurueta.units.Time timeInterval)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval.
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefCoordinateTransformationMatrixFromInterval

      public static CoordinateTransformation eciToEcefCoordinateTransformationMatrixFromInterval(double timeInterval)
      Computes ECI to ECEF coordinate transformation matrix taking into account Earth rotation during provided time interval.
      Parameters:
      timeInterval - a time interval expressed in seconds (s).
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefCoordinateTransformationMatrixFromAngle

      public static CoordinateTransformation eciToEcefCoordinateTransformationMatrixFromAngle(com.irurueta.units.Angle angle)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated.
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • eciToEcefCoordinateTransformationMatrixFromAngle

      public static CoordinateTransformation eciToEcefCoordinateTransformationMatrixFromAngle(double angle)
      Computes ECI to ECEF coordinate transformation matrix for provided Earth rotation angle.
      Parameters:
      angle - angle amount the Earth has rotated expressed in radians.
      Returns:
      a new ECI to ECEF coordinate transformation matrix.
    • clone

      protected Object clone() throws CloneNotSupportedException
      Makes a copy of this instance.
      Overrides:
      clone in class Object
      Returns:
      a copy of this instance.
      Throws:
      CloneNotSupportedException - if clone fails for some reason.