[wpimath] Add overloads for Transform2d and Transform3d (#5757)

Adds overloads for Transform2d() constructor to accept x, y, and heading and for Transform3d() to accept x, y, z and rotation as a shorthand for the normal constructors.
This commit is contained in:
Anit Mangal
2023-10-13 11:51:39 +05:30
committed by GitHub
parent 9a0aafd8ab
commit c0b4c6cce6
6 changed files with 56 additions and 0 deletions

View File

@@ -40,6 +40,18 @@ public class Transform2d {
m_rotation = rotation;
}
/**
* Constructs a transform with x and y translations instead of a separate Translation2d.
*
* @param x The x component of the translational component of the transform.
* @param y The y component of the translational component of the transform.
* @param rotation The rotational component of the transform.
*/
public Transform2d(double x, double y, Rotation2d rotation) {
m_translation = new Translation2d(x, y);
m_rotation = rotation;
}
/** Constructs the identity transform -- maps an initial pose to itself. */
public Transform2d() {
m_translation = new Translation2d();

View File

@@ -40,6 +40,19 @@ public class Transform3d {
m_rotation = rotation;
}
/**
* Constructs a transform with x, y, and z translations instead of a separate Translation3d.
*
* @param x The x component of the translational component of the transform.
* @param y The y component of the translational component of the transform.
* @param z The z component of the translational component of the transform.
* @param rotation The rotational component of the transform.
*/
public Transform3d(double x, double y, double z, Rotation3d rotation) {
m_translation = new Translation3d(x, y, z);
m_rotation = rotation;
}
/** Constructs the identity transform -- maps an initial pose to itself. */
public Transform3d() {
m_translation = new Translation3d();