Skip to content

Commit e37c357

Browse files
authored
[wpimath] Implement Translation3d.RotateAround (#7661)
1 parent 995bc98 commit e37c357

File tree

5 files changed

+94
-1
lines changed

5 files changed

+94
-1
lines changed

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
@@ -216,6 +216,17 @@ public Translation3d rotateBy(Rotation3d other) {
216216
return new Translation3d(qprime.getX(), qprime.getY(), qprime.getZ());
217217
}
218218

219+
/**
220+
* Rotates this translation around another translation in 3D space.
221+
*
222+
* @param other The other translation to rotate around.
223+
* @param rot The rotation to rotate the translation by.
224+
* @return The new rotated translation.
225+
*/
226+
public Translation3d rotateAround(Translation3d other, Rotation3d rot) {
227+
return this.minus(other).rotateBy(rot).plus(other);
228+
}
229+
219230
/**
220231
* Returns a Translation2d representing this Translation3d projected into the X-Y plane.
221232
*

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

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -148,6 +148,18 @@ class WPILIB_DLLEXPORT Translation3d {
148148
units::meter_t{qprime.Z()}};
149149
}
150150

151+
/**
152+
* Rotates this translation around another translation in 3D space.
153+
*
154+
* @param other The other translation to rotate around.
155+
* @param rot The rotation to rotate the translation by.
156+
* @return The new rotated translation.
157+
*/
158+
constexpr Translation3d RotateAround(const Translation3d& other,
159+
const Rotation3d& rot) const {
160+
return (*this - other).RotateBy(rot) + other;
161+
}
162+
151163
/**
152164
* Returns a Translation2d representing this Translation3d projected into the
153165
* X-Y plane.

wpimath/src/test/java/edu/wpi/first/math/geometry/Translation3dTest.java

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,40 @@ void testRotateBy() {
7878
() -> assertEquals(3.0, rotated3.getZ(), kEpsilon));
7979
}
8080

81+
@Test
82+
void testRotateAround() {
83+
var xAxis = VecBuilder.fill(1.0, 0.0, 0.0);
84+
var yAxis = VecBuilder.fill(0.0, 1.0, 0.0);
85+
var zAxis = VecBuilder.fill(0.0, 0.0, 1.0);
86+
87+
var translation = new Translation3d(1.0, 2.0, 3.0);
88+
var around = new Translation3d(3.0, 2.0, 1.0);
89+
90+
var rotated1 =
91+
translation.rotateAround(around, new Rotation3d(xAxis, Units.degreesToRadians(90.0)));
92+
93+
assertAll(
94+
() -> assertEquals(1.0, rotated1.getX(), kEpsilon),
95+
() -> assertEquals(0.0, rotated1.getY(), kEpsilon),
96+
() -> assertEquals(1.0, rotated1.getZ(), kEpsilon));
97+
98+
var rotated2 =
99+
translation.rotateAround(around, new Rotation3d(yAxis, Units.degreesToRadians(90.0)));
100+
101+
assertAll(
102+
() -> assertEquals(5.0, rotated2.getX(), kEpsilon),
103+
() -> assertEquals(2.0, rotated2.getY(), kEpsilon),
104+
() -> assertEquals(3.0, rotated2.getZ(), kEpsilon));
105+
106+
var rotated3 =
107+
translation.rotateAround(around, new Rotation3d(zAxis, Units.degreesToRadians(90.0)));
108+
109+
assertAll(
110+
() -> assertEquals(3.0, rotated3.getX(), kEpsilon),
111+
() -> assertEquals(0.0, rotated3.getY(), kEpsilon),
112+
() -> assertEquals(3.0, rotated3.getZ(), kEpsilon));
113+
}
114+
81115
@Test
82116
void testToTranslation2d() {
83117
var translation = new Translation3d(1.0, 2.0, 3.0);

wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,16 @@ TEST(Translation2dTest, RotateBy) {
3535
const auto rotated = another.RotateBy(90_deg);
3636

3737
EXPECT_NEAR(0.0, rotated.X().value(), 1e-9);
38-
EXPECT_DOUBLE_EQ(3.0, rotated.Y().value());
38+
EXPECT_NEAR(3.0, rotated.Y().value(), 1e-9);
39+
}
40+
41+
TEST(Translation2dTest, RotateAround) {
42+
const Translation2d translation{2_m, 1_m};
43+
const Translation2d other{3_m, 2_m};
44+
const auto rotated = translation.RotateAround(other, 180_deg);
45+
46+
EXPECT_NEAR(4.0, rotated.X().value(), 1e-9);
47+
EXPECT_NEAR(3.0, rotated.Y().value(), 1e-9);
3948
}
4049

4150
TEST(Translation2dTest, Multiplication) {

wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,33 @@ TEST(Translation3dTest, RotateBy) {
5757
EXPECT_NEAR(rotated3.Z().value(), 3.0, kEpsilon);
5858
}
5959

60+
TEST(Translation3dTest, RotateAround) {
61+
Eigen::Vector3d xAxis{1.0, 0.0, 0.0};
62+
Eigen::Vector3d yAxis{0.0, 1.0, 0.0};
63+
Eigen::Vector3d zAxis{0.0, 0.0, 1.0};
64+
65+
const Translation3d translation{1_m, 2_m, 3_m};
66+
const Translation3d around{3_m, 2_m, 1_m};
67+
68+
const auto rotated1 =
69+
translation.RotateAround(around, Rotation3d{xAxis, 90_deg});
70+
EXPECT_NEAR(rotated1.X().value(), 1.0, kEpsilon);
71+
EXPECT_NEAR(rotated1.Y().value(), 0.0, kEpsilon);
72+
EXPECT_NEAR(rotated1.Z().value(), 1.0, kEpsilon);
73+
74+
const auto rotated2 =
75+
translation.RotateAround(around, Rotation3d{yAxis, 90_deg});
76+
EXPECT_NEAR(rotated2.X().value(), 5.0, kEpsilon);
77+
EXPECT_NEAR(rotated2.Y().value(), 2.0, kEpsilon);
78+
EXPECT_NEAR(rotated2.Z().value(), 3.0, kEpsilon);
79+
80+
const auto rotated3 =
81+
translation.RotateAround(around, Rotation3d{zAxis, 90_deg});
82+
EXPECT_NEAR(rotated3.X().value(), 3.0, kEpsilon);
83+
EXPECT_NEAR(rotated3.Y().value(), 0.0, kEpsilon);
84+
EXPECT_NEAR(rotated3.Z().value(), 3.0, kEpsilon);
85+
}
86+
6087
TEST(Translation3dTest, ToTranslation2d) {
6188
Translation3d translation{1_m, 2_m, 3_m};
6289
Translation2d expected{1_m, 2_m};

0 commit comments

Comments
 (0)