Skip to content

Commit f445c9a

Browse files
committed
Add 2d to 3d constructors
1 parent 6adad7b commit f445c9a

File tree

8 files changed

+70
-0
lines changed

8 files changed

+70
-0
lines changed

wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,8 @@ public Pose3d(Distance x, Distance y, Distance z, Rotation3d rotation) {
8383
* Constructs a 3D pose from a 2D pose in the X-Y plane.
8484
*
8585
* @param pose The 2D pose.
86+
* @see Rotation3d#Rotation3d(Rotation2d)
87+
* @see Translation3d#Translation3d(Translation2d)
8688
*/
8789
public Pose3d(Pose2d pose) {
8890
m_translation = new Translation3d(pose.getX(), pose.getY(), 0.0);

wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -273,6 +273,17 @@ public Rotation3d(Vector<N3> initial, Vector<N3> last) {
273273
}
274274
}
275275

276+
/**
277+
* Constructs a 3D rotation from a 2D rotation in the X-Y plane.
278+
*
279+
* @param rotation The 2D rotation.
280+
* @see Pose3d#Pose3d(Pose2d)
281+
* @see Transform3d#Transform3d(Transform2d)
282+
*/
283+
public Rotation3d(Rotation2d rotation) {
284+
this(0.0, 0.0, rotation.getRadians());
285+
}
286+
276287
/**
277288
* Adds two rotations together.
278289
*

wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,18 @@ public Transform3d() {
8686
m_rotation = Rotation3d.kZero;
8787
}
8888

89+
/**
90+
* Constructs a 3D transform from a 2D transform in the X-Y plane.
91+
*
92+
* @param transform The 2D transform.
93+
* @see Rotation3d#Rotation3d(Rotation2d)
94+
* @see Translation3d#Translation3d(Translation2d)
95+
*/
96+
public Transform3d(Transform2d transform) {
97+
m_translation = new Translation3d(transform.getTranslation());
98+
m_rotation = new Rotation3d(transform.getRotation());
99+
}
100+
89101
/**
90102
* Multiplies the transform by the scalar.
91103
*

wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,17 @@ public Translation3d(Distance x, Distance y, Distance z) {
9292
this(x.in(Meters), y.in(Meters), z.in(Meters));
9393
}
9494

95+
/**
96+
* Constructs a 3D translation from a 2D translation in the X-Y plane.
97+
*
98+
* @param translation The 2D translation.
99+
* @see Pose3d#Pose3d(Pose2d)
100+
* @see Transform3d#Transform3d(Transform2d)
101+
*/
102+
public Translation3d(Translation2d translation) {
103+
this(translation.getX(), translation.getY(), 0.0);
104+
}
105+
95106
/**
96107
* Constructs a Translation3d from the provided translation vector's X, Y, and Z components. The
97108
* values are assumed to be in meters.

wpimath/src/main/native/include/frc/geometry/Pose3d.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,8 @@ class WPILIB_DLLEXPORT Pose3d {
5858
* Constructs a 3D pose from a 2D pose in the X-Y plane.
5959
*
6060
* @param pose The 2D pose.
61+
* @see Rotation3d(Rotation2d)
62+
* @see Translation3d(Translation2d)
6163
*/
6264
constexpr explicit Pose3d(const Pose2d& pose)
6365
: m_translation{pose.X(), pose.Y(), 0_m},

wpimath/src/main/native/include/frc/geometry/Rotation3d.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -229,6 +229,16 @@ class WPILIB_DLLEXPORT Rotation3d {
229229
}
230230
}
231231

232+
/**
233+
* Constructs a 3D rotation from a 2D rotation in the X-Y plane.
234+
*
235+
* @param rotation The 2D rotation.
236+
* @see Pose3d(Pose2d)
237+
* @see Transform3d(Transform2d)
238+
*/
239+
constexpr explicit Rotation3d(const Rotation2d& rotation)
240+
: Rotation3d{0_rad, 0_rad, rotation.Radians()} {}
241+
232242
/**
233243
* Adds two rotations together.
234244
*

wpimath/src/main/native/include/frc/geometry/Transform3d.h

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
#include <wpi/SymbolExports.h>
1010

11+
#include "frc/geometry/Transform2d.h"
1112
#include "frc/geometry/Translation3d.h"
1213

1314
namespace frc {
@@ -55,6 +56,17 @@ class WPILIB_DLLEXPORT Transform3d {
5556
*/
5657
constexpr Transform3d() = default;
5758

59+
/**
60+
* Constructs a 3D transform from a 2D transform in the X-Y plane.
61+
**
62+
* @param transform The 2D transform.
63+
* @see Rotation3d(Rotation2d)
64+
* @see Translation3d(Translation2d)
65+
*/
66+
constexpr explicit Transform3d(const frc::Transform2d& transform)
67+
: m_translation{frc::Translation3d{transform.Translation()}},
68+
m_rotation{frc::Rotation3d{transform.Rotation()}} {}
69+
5870
/**
5971
* Returns the translation component of the transformation.
6072
*

wpimath/src/main/native/include/frc/geometry/Translation3d.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,16 @@ class WPILIB_DLLEXPORT Translation3d {
6666
m_y{units::meter_t{vector.y()}},
6767
m_z{units::meter_t{vector.z()}} {}
6868

69+
/**
70+
* Constructs a 3D translation from a 2D translation in the X-Y plane.
71+
*
72+
* @param translation The 2D translation.
73+
* @see Pose3d(Pose2d)
74+
* @see Transform3d(Transform2d)
75+
*/
76+
constexpr explicit Translation3d(const Translation2d& translation)
77+
: Translation3d{translation.X(), translation.Y(), 0_m} {}
78+
6979
/**
7080
* Calculates the distance between two translations in 3D space.
7181
*

0 commit comments

Comments
 (0)