Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[wpimath] Add overloads for Transform2d and Transform3d #5757

Merged
merged 11 commits into from
Oct 13, 2023
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,18 @@ public Transform2d(Translation2d translation, Rotation2d rotation) {
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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,19 @@ public Transform3d(Translation3d translation, Rotation3d rotation) {
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();
Expand Down
4 changes: 4 additions & 0 deletions wpimath/src/main/native/cpp/geometry/Transform3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,10 @@ Transform3d::Transform3d(Pose3d initial, Pose3d final) {
Transform3d::Transform3d(Translation3d translation, Rotation3d rotation)
: m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}

Transform3d::Transform3d(units::meter_t x, units::meter_t y, units::meter_t z,
Rotation3d rotation)
: m_translation(x, y, z), m_rotation(std::move(rotation)) {}

Transform3d Transform3d::Inverse() const {
// We are rotating the difference between the translations
// using a clockwise rotation matrix. This transforms the global
Expand Down
11 changes: 11 additions & 0 deletions wpimath/src/main/native/include/frc/geometry/Transform2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,17 @@ class WPILIB_DLLEXPORT Transform2d {
*/
constexpr Transform2d(Translation2d translation, Rotation2d 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.
*/
constexpr Transform2d(units::meter_t x, units::meter_t y,
Rotation2d rotation);

/**
* Constructs the identity transform -- maps an initial pose to itself.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,10 @@ constexpr Transform2d::Transform2d(Translation2d translation,
Rotation2d rotation)
: m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}

constexpr Transform2d::Transform2d(units::meter_t x, units::meter_t y,
Rotation2d rotation)
: m_translation(x, y), m_rotation(std::move(rotation)) {}

constexpr Transform2d Transform2d::Inverse() const {
// We are rotating the difference between the translations
// using a clockwise rotation matrix. This transforms the global
Expand Down
12 changes: 12 additions & 0 deletions wpimath/src/main/native/include/frc/geometry/Transform3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,18 @@ class WPILIB_DLLEXPORT Transform3d {
*/
Transform3d(Translation3d translation, Rotation3d 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.
*/
Transform3d(units::meter_t x, units::meter_t y, units::meter_t z,
Rotation3d rotation);

/**
* Constructs the identity transform -- maps an initial pose to itself.
*/
Expand Down
Loading